Tugbot Driver Nodes – Full Example
The following describes the nodes that are provided by MOV.AI in the Tugbot Sim Drivers subflow for controlling a Tugbot robot in Gazebo Fortress. This section describes the ready-made nodes that provide the drivers in MOV.AI Flow™ for reading the sensors and actuating (operating) a Tugbot robot.
-
[ Ignition_sim_base] – Appears first in the robot_simuation_drivers subflow so that it can use the clock from the simulator and set the initial parameters for this subflow.
-
Ignition_robot_state – A subflow that creates a bridge between MOV.AI and the Gazebo Fortress PosePublisher plugin in your robot. It also generates the TFs of all parts of the robot.
Note – You may refer to http://wiki.ros.org/tf for a description of a TF.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
frame_id – Specifies the name of the frame that you want as a parent of the TFs to be generated.
generate_tfs – Publishes the links’ poses as TFs.Ports –
output – robot_pose (geometry_msgs/TransformStamped)
-
Ignition_diffdrive – A subflow that creates a bridge between MOV.AI and the Ignition DiffDrive plugin in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topics /cmd_vel and /odom that you want.Ports –
input – cmd_vel (geometry_msgs/Twist)
output – odom (nav_msgs/Odometry) -
/ Ignition_joint_cmd_controller / Ignition_joint_position_controller – A subflow that controls robot joints based on effort, velocity or position commands.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topic /cmd that you want.
joint_name – Specifies the name of the joint to be controlled, as declared in the SDF file.
child_name – Specifies the name of the link to be controlled by this joint, as declared in the SDF file.Ports –
input – cmd (std_msgs/Float64)
-
Ignition_battery – A subflow that creates a bridge between MOV.AI and the Ignition LinearBatteryPlugin plugin in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topics /state, /charge and /stop_charge that you want.
battery_name – Specifies the name of the battery, as declared in the SDF file.Ports –
input – charge (std_msgs/Bool) and stop_charge (std_msgs/Bool)
output – state (sensor_msgs/BatteryState) -
Ignition_imu – A subflow that creates a bridge between MOV.AI and the IMU sensor in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topic /imu that you want.
frame_name – Specifies the name of the link in which this sensor is located, as declared in the SDF file.
sensor_name – Specifies the name of this sensor, as declared in the SDF file.Ports –
output – imu (sensor_msgs/Imu)
-
Ignition_lidar_2D – A subflow that creates a bridge between MOV.AI and the LiDAR sensor in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topic /scan that you want.
frame_name – Specifies the name of the link in which this sensor is located, as declared in the SDF file.
sensor_name – Specifies the name of this sensor, as declared in the SDF file.Ports –
output – scan (sensor_msgs/LaserScan)
-
Ignition_lidar_3D – A subflow that creates a bridge between MOV.AI and the LiDAR sensor in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topic /scan and /points that you want.
frame_name – Specifies the name of the link in which this sensor is located, as declared in the SDF file.
sensor_name – Specifies the name of this sensor, as declared in the SDF file.Ports –
output – scan (sensor_msgs/LaserScan) and points (sensor_msgs/PointCloud2)
-
Ignition_camera_rgb – A subflow that creates a bridge between MOV.AI and sensor camera type: rgb in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topic /scan and /points that you want.
frame_name – Specifies the name of the link in which this sensor is located, as declared in the SDF file.
sensor_name – Specifies the name of this sensor, as declared in the SDF file.
lens_pose – Specifies the position of the sensor, as declared in the SDF file (x y z R P Y).Ports –
output – image_raw (sensor_msgs/Image) and camera_info (sensor_msgs/CameraInfo)
-
Ignition_camera_depth – A subflow that creates a bridge between MOV.AI and the sensor camera type: depth, in your robot.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this example, it is tugbot.
remap_topic – Specifies the namespace of the topic /depth_image, /camera_info and /depth_image/points that you want.
frame_name – Specifies the name of the link in which this sensor is located, as declared in the SDF file.
sensor_name – Specifies the name of this sensor, as declared in the SDF file.
lens_pose – Specifies the position of the sensor, as declared in the SDF file (x y z R P Y).Ports –
output – depth_image (sensor_msgs/Image), camera_info (sensor_msgs/CameraInfo) and depth_image/points (sensor_msgs/PointCloud2)
-
Ignition_camera_rgbD – A subflow that creates a bridge between MOV.AI and the sensor camera type: rgbd (RGB + Depth), which creates both color and depth images.
Parameters –
robot_name – Specifies the robot name that was defined inside the SDF file. In this
example, it is tugbot.
remap_topic – Specifies the namespace of the topic /image, /depth_image /camera_info and /depth_image/points that you want.
frame_name – Specifies the name of the link in which this sensor is located, as declared in the SDF file.
sensor_name – Specifies the name of this sensor, as declared in the SDF file.
lens_pose – Specifies the position of the sensor, as declared in the SDF file (x y z R P Y).Ports –
output – image (sensor_msgs/Image), depth_image (sensor_msgs/Image), camera_info (sensor_msgs/CameraInfo) and depth_image/points (sensor_msgs/PointCloud2)
Updated over 2 years ago