ROS Bridge¶
The ROS Bridge allows to integrate PlatformPilot into a ROS / ROS 2 environment, such that it is possible to control the platform via ROS as well as visualize all data in RViz.
Installation¶
It is assumed that a ROS workspace has already been setup on the platform’s PC, for example ~/ros_workspace/
.
To install the ROS Bridge:
Note
Currently ROS and ROS 2 are being maintained in different branches on Github. The default branch is set to ROS 2.
cd ~/ros_workspace/src/
git clone https://github.com/neobotix/pilot-ros-bridge.git
cd ~/ros_workspace/
# For ROS 2
colcon build --symlink-install
# For ROS
catkin_make
On ROS 2 side, the package depends on neo_srvs2 and neo_msgs2. Similarly, neo_msgs and neo_srvs for ROS.
On Pilot side, the package depends on an already installed neobotix-pilot-core
or neobotix-pilot-gtkgui
package.
Running¶
To run the ROS bridge on the platform:
source ~/ros_workspace/devel/setup.bash
# For ROS 2
ros2 launch pilot_ros_bridge mpo_700.launch
# For ROS
roslaunch pilot_ros_bridge mpo_700.launch
Replace mpo_700.launch
with mpo_500.launch
or mp_400.launch
, depending on your platform.
It is also possible to run the ROS bridge on another PC, by adapting the pilot_node
param in the launch file:
<param name="pilot_node" type="str" value="192.168.0.50:5555"/>
Replace 192.168.0.50
with the actual IP address of the platform.
In addition you can disable user authentication on the TCP server to allow for all functionality via the ROS Bridge.
To do this create a config file config/local/TcpServer.json
:
{
"use_authentication": false
}
This is only necessary when running the ROS Bridge on another PC.
Topics¶
The following topics are enabled on the ROS bridge by default.
You can add more by adapting the config file config/default/generic/Pilot_ROS_Bridge.json
in pilot-ros-bridge
.
Export¶
"export_map": [
["platform.odometry", "/odom"],
["sensors.laser_scan.lidar_1", "/lidar_1/scan"],
["sensors.laser_scan.lidar_2", "/lidar_2/scan"],
["sensors.filtered_scan.lidar_1", "/lidar_1/scan_filtered"],
["sensors.filtered_scan.lidar_2", "/lidar_2/scan_filtered"],
["kinematics.drive_state", "/drives/joint_states"],
["mapping.grid_map", "/mapping/map"],
["mapping.grid_map_tile", "/mapping/map_tile"],
["mapping.grid_map_tile_ref", "/mapping/map_tile_ref"],
["navigation.grid_map", "/map"],
["navigation.grid_map_tile", "/map_tile"],
["navigation.map_pose", "/map_pose"],
["navigation.map_particles", "/particlecloud"],
["navigation.road_map", "/road_map"],
["navigation.global_path", "/global_path"],
["navigation.local_path", "/local_path"],
["navigation.local_cost_map", "/local_cost_map"],
["navigation.local_cost_map_overlay", "/local_cost_map_overlay"],
["navigation.global_cost_map", "/global_cost_map"],
["navigation.global_cost_map_overlay", "/global_cost_map_overlay"],
["local_planner.target_pose", "/local_planner/target_pose"],
["local_planner.predicted_pose", "/local_planner/predicted_pose"]
]
Import¶
"import_map": [
[["/cmd_vel", "geometry_msgs/Twist"], "platform.velocity_cmd"],
[["/initialpose", "geometry_msgs/PoseWithCovarianceStamped"], "navigation.initial_pose"],
[["/goal", "geometry_msgs/PoseStamped"], "navigation.new_goal_pose"]
]
Note
In ROS 2, 2D Goal Pose tool from RViz2 is utilized for sending the goal to the /goal topic. Similarly user can use the same topic from the application side.