This page introduces the usage of sync_set_stcm, including how to upload the STCM map to the robot via the sync_set_stcm service.
Contents
Environment Setup
software platform
- Ubuntu 20.04 X86
- ROS Noetic
hardware platform
Choose any one below:
- Slamware Kit (User Robot System based on Slamware Solution)
- robot base systems like Apollo/Ares/Athena
Sample Code Download
Compile and Run
- Download the Slamware ROS SDK along with ROS examples.
- Place the 'src' folder from the ROS SDK into an empty working directory, such as 'catkin_ws'. Also, put the 'slamware_ros_sample' folder from the ROS examples into the 'src' folder.
mkdir -p catkin_ws/src cd catkin_ws/src
- Initialize the workspace using the Catkin tool.
catkin_init_workspace
- Compile.
cd .. catkin_make
- Set up workspace environment.
source devel/setup.bash
- Launch the slamware_ros_sdk_server_node node. Select the corresponding IP according to the mode.
roslaunch slamware_ros_sdk slamware_ros_sdk_server_node.launch ip_address:=10.6.128.141 // Station mode // If in AP mode, the IP address is 192.168.11.1
- Open another terminal, repeat step 5, and start the sync_set_stcm_node node.
roslaunch slamware_ros_sample sync_set_stcm.launch // In the launch file, there is a default definition for the map_file_name parameter, indicating the path and filename where the map is saved. you can adjust parameters manually.
- At this point, observe the RVIZ interface; if the map file is successfully located, the map will be uploaded, and the map in RVIZ will also change accordingly. Otherwise, an error will occur.
Code Description
sync_set_stcm
int main (int argc, char **argv) { std::string map_file_name; long data_size; ros::init(argc, argv, "sync_set_stcm_node"); ros::NodeHandle nh("~"); ros::ServiceClient client = nh.serviceClient<slamware_ros_sdk::SyncSetStcm>("/slamware_ros_sdk_server_node/sync_set_stcm"); slamware_ros_sdk::SyncSetStcm srv; //get file name from paramter server if (!nh.getParam("map_file_name",map_file_name)) { ROS_ERROR("invalied file path......"); return 1; } ROS_INFO("map file path: %s",map_file_name.c_str()); //open map file and get data std::ifstream fin(map_file_name ,std::ios::in | std::ios::binary | std::ios::ate); if(!fin.is_open()) { ROS_ERROR("open map file failed......"); return 1; } ROS_INFO("open map file success,reading data......"); data_size = fin.tellg(); fin.seekg(0,std::ios::beg); srv.request.raw_stcm.resize(data_size); fin.read(reinterpret_cast<char *>(srv.request.raw_stcm.data()),data_size*sizeof(srv.request.raw_stcm.front())); fin.close(); ROS_INFO("raw_stcm data size: %zu",srv.request.raw_stcm.size()); //set robot pose srv.request.robot_pose.position.x = 0; srv.request.robot_pose.position.y = 0; srv.request.robot_pose.position.z = 0; srv.request.robot_pose.orientation.x = 0; srv.request.robot_pose.orientation.y = 0; srv.request.robot_pose.orientation.z = 0; srv.request.robot_pose.orientation.w = 1; //call service if (client.call(srv)) { ROS_INFO("set stcm map success......"); } else { ROS_ERROR("Failed to set stcm map......"); return 1; } return 0; }