本页介绍了sync_get_stcm的用法, 包含如何通过sync_get_stcm服务获取stcm地图。
本页内容
运行环境准备
软件平台
- Ubuntu 16.04 X86
- ROS Kinetic
硬件平台
(以下任选其一)
- Slamware 套装 (基于Slamware导航方案的用户机器人系统)
- Apollo/Ares/Athena等底盘系统
- Mapper
编译运行
1.下载Slamware ROS SDK以及ROS例程。
2.将ROS sdk中的src文件夹放入一个空的工作目录,如:catkin_ws。将ROS 例程中的slamware_ros_sample文件夹也放入src文件夹下。使用catkin工具初始化工作空间。
cd catkin_ws/src catkin_init_workspace
3.编译
cd .. catkin_make
4.配置工作空间系统环境
source devel/setup.bash
5.启动slamware_ros_sdk_server_node节点
roslaunch slamware_ros_sdk slamware_ros_sdk_server_node.launch ip_address:=10.6.128.141 //如果是AP模式,ip_address是192.168.11.1
6.重新打开一个终端窗口,重复第4步,并启动sync_get_stcm_node节点
roslaunch slamware_ros_sample sync_get_stcm.launch //launch文件中有定义默认的map_file_name参数,指明地图保存的路径和文件名称。如果不用默认参数,可自行传参。
7.此时观察slamware_ros_sample下,会生成一个map的文件夹,里面会生成data.map的文件。
代码描述
sync_get_stcm
int main (int argc, char **argv)
{
std::string map_file_name;
ros::init(argc, argv, "sync_set_stcm_node");
ros::NodeHandle nh("~");
ros::ServiceClient client = nh.serviceClient<slamware_ros_sdk::SyncGetStcm>("/slamware_ros_sdk_server_node/sync_get_stcm");
slamware_ros_sdk::SyncGetStcm srv;
//get file name from paramter server
if (!nh.getParam("map_file_name",map_file_name))
{
ROS_ERROR("invalied file path......");
return 1;
}
//call service
if (client.call(srv))
{
ROS_INFO("get raw_stcm data success,writing to file......");
//check whether the target folder exists. create one if not
std::string dir;
dir = map_file_name.substr(0,map_file_name.rfind("/"));
if(access(dir.c_str(),0))
{
std::string cmd = "mkdir -p " + dir;
system(cmd.c_str());
}
std::ofstream fout(map_file_name, std::ios::out | std::ios::binary);
fout.write(reinterpret_cast<char *>(srv.response.raw_stcm.data()),(srv.response.raw_stcm.size()) * sizeof(srv.response.raw_stcm.front()));
fout.close();
ROS_INFO("raw_stcm data size: %zu",srv.response.raw_stcm.size());
ROS_INFO("save map at %s success......",map_file_name.c_str());
}
else
{
ROS_ERROR("Failed to get raw_stcm data......");
return 1;
}
return 0;
}
