ROS interface plugin for Gazebo. More...
#include <gazebo_ros_interface_plugin.h>
Public Member Functions | |
GazeboRosInterfacePlugin () | |
void | InitializeParams () |
void | Publish () |
~GazeboRosInterfacePlugin () | |
Protected Member Functions | |
void | Load (physics::WorldPtr _world, sdf::ElementPtr _sdf) |
void | OnUpdate (const common::UpdateInfo &) |
This gets called by the world update start event. | |
Private Member Functions | |
template<typename GazeboMsgT , typename RosMsgT > | |
void | ConnectHelper (void(GazeboRosInterfacePlugin::*fp)(const boost::shared_ptr< GazeboMsgT const > &, ros::Publisher), GazeboRosInterfacePlugin *ptr, std::string gazeboNamespace, std::string gazeboTopicName, std::string rosTopicName, transport::NodePtr gz_node_handle) |
Provides a way for GzConnectGazeboToRosTopicMsgCallback() to connect a Gazebo subscriber to a ROS publisher. | |
void | ConvertHeaderGzToRos (const gz_std_msgs::Header &gz_header, std_msgs::Header_< std::allocator< void > > *ros_header) |
void | ConvertHeaderRosToGz (const std_msgs::Header_< std::allocator< void > > &ros_header, gz_std_msgs::Header *gz_header) |
template<typename T > | |
transport::PublisherPtr | FindOrMakeGazeboPublisher (std::string topic) |
Looks if a publisher on the provided topic already exists, and returns it. If no publisher exists, this method creates one and returns that instead. | |
void | GzActuatorsMsgCallback (GzActuatorsMsgPtr &gz_actuators_msg, ros::Publisher ros_publisher) |
void | GzBroadcastTransformMsgCallback (GzTransformStampedWithFrameIdsMsgPtr &broadcast_transform_msg) |
This is a special-case callback which listens for Gazebo "Transform" messages. Upon receiving one it broadcasts the transform on the ROS system (using transform_broadcast()). | |
void | GzConnectGazeboToRosTopicMsgCallback (GzConnectGazeboToRosTopicMsgPtr &gz_connect_gazebo_to_ros_topic_msg) |
void | GzConnectRosToGazeboTopicMsgCallback (GzConnectRosToGazeboTopicMsgPtr &gz_connect_ros_to_gazebo_topic_msg) |
Subscribes to the provided ROS topic and publishes on the provided Gazebo topic (all info contained within the message). | |
void | GzFloat32MsgCallback (GzFloat32MsgPtr &gz_float_32_msg, ros::Publisher ros_publisher) |
void | GzFluidPressureMsgCallback (GzFluidPressureMsgPtr &gz_fluid_pressure_msg, ros::Publisher ros_publisher) |
void | GzImuMsgCallback (GzImuPtr &gz_imu_msg, ros::Publisher ros_publisher) |
void | GzJointStateMsgCallback (GzJointStateMsgPtr &gz_joint_state_msg, ros::Publisher ros_publisher) |
void | GzMagneticFieldMsgCallback (GzMagneticFieldMsgPtr &gz_magnetic_field_msg, ros::Publisher ros_publisher) |
void | GzNavSatFixCallback (GzNavSatFixPtr &gz_nav_sat_fix_msg, ros::Publisher ros_publisher) |
void | GzOdometryMsgCallback (GzOdometryMsgPtr &gz_odometry_msg, ros::Publisher ros_publisher) |
void | GzPoseMsgCallback (GzPoseMsgPtr &gz_pose_msg, ros::Publisher ros_publisher) |
void | GzPoseWithCovarianceStampedMsgCallback (GzPoseWithCovarianceStampedMsgPtr &gz_pose_with_covariance_stamped_msg, ros::Publisher ros_publisher) |
void | GzTransformStampedMsgCallback (GzTransformStampedMsgPtr &gz_transform_stamped_msg, ros::Publisher ros_publisher) |
void | GzTwistStampedMsgCallback (GzTwistStampedMsgPtr &gz_twist_stamped_msg, ros::Publisher ros_publisher) |
void | GzVector3dStampedMsgCallback (GzVector3dStampedMsgPtr &gz_vector_3d_stamped_msg, ros::Publisher ros_publisher) |
void | GzWindSpeedMsgCallback (GzWindSpeedMsgPtr &gz_wind_speed_msg, ros::Publisher ros_publisher) |
void | GzWrenchStampedMsgCallback (GzWrenchStampedMsgPtr &gz_wrench_stamped_msg, ros::Publisher ros_publisher) |
void | RosActuatorsMsgCallback (const mav_msgs::ActuatorsConstPtr &ros_actuators_msg_ptr, gazebo::transport::PublisherPtr gz_publisher_ptr) |
void | RosCommandMotorSpeedMsgCallback (const mav_msgs::ActuatorsConstPtr &ros_command_motor_speed_msg_ptr, gazebo::transport::PublisherPtr gz_publisher_ptr) |
void | RosRollPitchYawrateThrustMsgCallback (const mav_msgs::RollPitchYawrateThrustConstPtr &ros_roll_pitch_yawrate_thrust_msg_ptr, gazebo::transport::PublisherPtr gz_publisher_ptr) |
void | RosWindSpeedMsgCallback (const rotors_comm::WindSpeedConstPtr &ros_wind_speed_msg_ptr, gazebo::transport::PublisherPtr gz_publisher_ptr) |
Private Attributes | |
transport::SubscriberPtr | gz_broadcast_transform_sub_ |
transport::SubscriberPtr | gz_connect_gazebo_to_ros_topic_sub_ |
transport::SubscriberPtr | gz_connect_ros_to_gazebo_topic_sub_ |
transport::NodePtr | gz_node_handle_ |
Handle for the Gazebo node. | |
std::vector < gazebo::transport::NodePtr > | nodePtrs_ |
mav_msgs::Actuators | ros_actuators_msg_ |
std_msgs::Float32 | ros_float_32_msg_ |
sensor_msgs::FluidPressure | ros_fluid_pressure_msg_ |
sensor_msgs::Imu | ros_imu_msg_ |
sensor_msgs::JointState | ros_joint_state_msg_ |
sensor_msgs::MagneticField | ros_magnetic_field_msg_ |
sensor_msgs::NavSatFix | ros_nav_sat_fix_msg_ |
ros::NodeHandle * | ros_node_handle_ |
Handle for the ROS node. | |
nav_msgs::Odometry | ros_odometry_msg_ |
geometry_msgs::Pose | ros_pose_msg_ |
geometry_msgs::PoseWithCovarianceStamped | ros_pose_with_covariance_stamped_msg_ |
geometry_msgs::PointStamped | ros_position_stamped_msg_ |
geometry_msgs::TransformStamped | ros_transform_stamped_msg_ |
geometry_msgs::TwistStamped | ros_twist_stamped_msg_ |
rotors_comm::WindSpeed | ros_wind_speed_msg_ |
geometry_msgs::WrenchStamped | ros_wrench_stamped_msg_ |
std::vector < gazebo::transport::SubscriberPtr > | subscriberPtrs_ |
tf::Transform | tf_ |
tf::TransformBroadcaster | transform_broadcaster_ |
event::ConnectionPtr | updateConnection_ |
Pointer to the update event connection. | |
physics::WorldPtr | world_ |
Pointer to the world. |
ROS interface plugin for Gazebo.
This routes messages to/from Gazebo and ROS. This is used so that individual plugins are not ROS dependent. This is a WorldPlugin, only one of these is designed to be enabled per Gazebo world.
Definition at line 123 of file gazebo_ros_interface_plugin.h.
Definition at line 32 of file gazebo_ros_interface_plugin.cpp.
Definition at line 35 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::ConnectHelper | ( | void(GazeboRosInterfacePlugin::*)(const boost::shared_ptr< GazeboMsgT const > &, ros::Publisher) | fp, |
GazeboRosInterfacePlugin * | ptr, | ||
std::string | gazeboNamespace, | ||
std::string | gazeboTopicName, | ||
std::string | rosTopicName, | ||
transport::NodePtr | gz_node_handle | ||
) | [private] |
Provides a way for GzConnectGazeboToRosTopicMsgCallback() to connect a Gazebo subscriber to a ROS publisher.
GazeboMsgT The type of the message that will be subscribed to the Gazebo framework. RosMsgT The type of the message published to the ROS framework.
Definition at line 137 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::ConvertHeaderGzToRos | ( | const gz_std_msgs::Header & | gz_header, |
std_msgs::Header_< std::allocator< void > > * | ros_header | ||
) | [private] |
Definition at line 375 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::ConvertHeaderRosToGz | ( | const std_msgs::Header_< std::allocator< void > > & | ros_header, |
gz_std_msgs::Header * | gz_header | ||
) | [private] |
Definition at line 383 of file gazebo_ros_interface_plugin.cpp.
transport::PublisherPtr gazebo::GazeboRosInterfacePlugin::FindOrMakeGazeboPublisher | ( | std::string | topic | ) | [private] |
Looks if a publisher on the provided topic already exists, and returns it. If no publisher exists, this method creates one and returns that instead.
void gazebo::GazeboRosInterfacePlugin::GzActuatorsMsgCallback | ( | GzActuatorsMsgPtr & | gz_actuators_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 395 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzBroadcastTransformMsgCallback | ( | GzTransformStampedWithFrameIdsMsgPtr & | broadcast_transform_msg | ) | [private] |
This is a special-case callback which listens for Gazebo "Transform" messages. Upon receiving one it broadcasts the transform on the ROS system (using transform_broadcast()).
Definition at line 1032 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzConnectGazeboToRosTopicMsgCallback | ( | GzConnectGazeboToRosTopicMsgPtr & | gz_connect_gazebo_to_ros_topic_msg | ) | [private] |
Definition at line 171 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzConnectRosToGazeboTopicMsgCallback | ( | GzConnectRosToGazeboTopicMsgPtr & | gz_connect_ros_to_gazebo_topic_msg | ) | [private] |
Subscribes to the provided ROS topic and publishes on the provided Gazebo topic (all info contained within the message).
Will create a Gazebo publisher if one doesn't already exist.
Definition at line 279 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzFloat32MsgCallback | ( | GzFloat32MsgPtr & | gz_float_32_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 413 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzFluidPressureMsgCallback | ( | GzFluidPressureMsgPtr & | gz_fluid_pressure_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 422 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzImuMsgCallback | ( | GzImuPtr & | gz_imu_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 440 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzJointStateMsgCallback | ( | GzJointStateMsgPtr & | gz_joint_state_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 499 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzMagneticFieldMsgCallback | ( | GzMagneticFieldMsgPtr & | gz_magnetic_field_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 518 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzNavSatFixCallback | ( | GzNavSatFixPtr & | gz_nav_sat_fix_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 552 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzOdometryMsgCallback | ( | GzOdometryMsgPtr & | gz_odometry_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 651 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzPoseMsgCallback | ( | GzPoseMsgPtr & | gz_pose_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 713 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzPoseWithCovarianceStampedMsgCallback | ( | GzPoseWithCovarianceStampedMsgPtr & | gz_pose_with_covariance_stamped_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 727 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzTransformStampedMsgCallback | ( | GzTransformStampedMsgPtr & | gz_transform_stamped_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 797 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzTwistStampedMsgCallback | ( | GzTwistStampedMsgPtr & | gz_twist_stamped_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 831 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzVector3dStampedMsgCallback | ( | GzVector3dStampedMsgPtr & | gz_vector_3d_stamped_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 860 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzWindSpeedMsgCallback | ( | GzWindSpeedMsgPtr & | gz_wind_speed_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 880 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::GzWrenchStampedMsgCallback | ( | GzWrenchStampedMsgPtr & | gz_wrench_stamped_msg, |
ros::Publisher | ros_publisher | ||
) | [private] |
Definition at line 901 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::Load | ( | physics::WorldPtr | _world, |
sdf::ElementPtr | _sdf | ||
) | [protected] |
Store the pointer to the model.
Definition at line 44 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::OnUpdate | ( | const common::UpdateInfo & | _info | ) | [protected] |
This gets called by the world update start event.
Calculates IMU parameters and then publishes one IMU message.
Definition at line 104 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::RosActuatorsMsgCallback | ( | const mav_msgs::ActuatorsConstPtr & | ros_actuators_msg_ptr, |
gazebo::transport::PublisherPtr | gz_publisher_ptr | ||
) | [private] |
Definition at line 937 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::RosCommandMotorSpeedMsgCallback | ( | const mav_msgs::ActuatorsConstPtr & | ros_command_motor_speed_msg_ptr, |
gazebo::transport::PublisherPtr | gz_publisher_ptr | ||
) | [private] |
Definition at line 966 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::RosRollPitchYawrateThrustMsgCallback | ( | const mav_msgs::RollPitchYawrateThrustConstPtr & | ros_roll_pitch_yawrate_thrust_msg_ptr, |
gazebo::transport::PublisherPtr | gz_publisher_ptr | ||
) | [private] |
Definition at line 982 of file gazebo_ros_interface_plugin.cpp.
void gazebo::GazeboRosInterfacePlugin::RosWindSpeedMsgCallback | ( | const rotors_comm::WindSpeedConstPtr & | ros_wind_speed_msg_ptr, |
gazebo::transport::PublisherPtr | gz_publisher_ptr | ||
) | [private] |
Definition at line 1011 of file gazebo_ros_interface_plugin.cpp.
transport::SubscriberPtr gazebo::GazeboRosInterfacePlugin::gz_broadcast_transform_sub_ [private] |
Definition at line 321 of file gazebo_ros_interface_plugin.h.
transport::SubscriberPtr gazebo::GazeboRosInterfacePlugin::gz_connect_gazebo_to_ros_topic_sub_ [private] |
Definition at line 174 of file gazebo_ros_interface_plugin.h.
transport::SubscriberPtr gazebo::GazeboRosInterfacePlugin::gz_connect_ros_to_gazebo_topic_sub_ [private] |
Definition at line 182 of file gazebo_ros_interface_plugin.h.
transport::NodePtr gazebo::GazeboRosInterfacePlugin::gz_node_handle_ [private] |
Handle for the Gazebo node.
Definition at line 159 of file gazebo_ros_interface_plugin.h.
std::vector<gazebo::transport::NodePtr> gazebo::GazeboRosInterfacePlugin::nodePtrs_ [private] |
Definition at line 153 of file gazebo_ros_interface_plugin.h.
mav_msgs::Actuators gazebo::GazeboRosInterfacePlugin::ros_actuators_msg_ [private] |
Definition at line 217 of file gazebo_ros_interface_plugin.h.
std_msgs::Float32 gazebo::GazeboRosInterfacePlugin::ros_float_32_msg_ [private] |
Definition at line 222 of file gazebo_ros_interface_plugin.h.
sensor_msgs::FluidPressure gazebo::GazeboRosInterfacePlugin::ros_fluid_pressure_msg_ [private] |
Definition at line 227 of file gazebo_ros_interface_plugin.h.
sensor_msgs::Imu gazebo::GazeboRosInterfacePlugin::ros_imu_msg_ [private] |
Definition at line 231 of file gazebo_ros_interface_plugin.h.
sensor_msgs::JointState gazebo::GazeboRosInterfacePlugin::ros_joint_state_msg_ [private] |
Definition at line 236 of file gazebo_ros_interface_plugin.h.
sensor_msgs::MagneticField gazebo::GazeboRosInterfacePlugin::ros_magnetic_field_msg_ [private] |
Definition at line 241 of file gazebo_ros_interface_plugin.h.
sensor_msgs::NavSatFix gazebo::GazeboRosInterfacePlugin::ros_nav_sat_fix_msg_ [private] |
Definition at line 246 of file gazebo_ros_interface_plugin.h.
Handle for the ROS node.
Definition at line 162 of file gazebo_ros_interface_plugin.h.
nav_msgs::Odometry gazebo::GazeboRosInterfacePlugin::ros_odometry_msg_ [private] |
Definition at line 251 of file gazebo_ros_interface_plugin.h.
Definition at line 256 of file gazebo_ros_interface_plugin.h.
geometry_msgs::PoseWithCovarianceStamped gazebo::GazeboRosInterfacePlugin::ros_pose_with_covariance_stamped_msg_ [private] |
Definition at line 263 of file gazebo_ros_interface_plugin.h.
geometry_msgs::PointStamped gazebo::GazeboRosInterfacePlugin::ros_position_stamped_msg_ [private] |
Definition at line 269 of file gazebo_ros_interface_plugin.h.
geometry_msgs::TransformStamped gazebo::GazeboRosInterfacePlugin::ros_transform_stamped_msg_ [private] |
Definition at line 275 of file gazebo_ros_interface_plugin.h.
geometry_msgs::TwistStamped gazebo::GazeboRosInterfacePlugin::ros_twist_stamped_msg_ [private] |
Definition at line 280 of file gazebo_ros_interface_plugin.h.
rotors_comm::WindSpeed gazebo::GazeboRosInterfacePlugin::ros_wind_speed_msg_ [private] |
Definition at line 285 of file gazebo_ros_interface_plugin.h.
geometry_msgs::WrenchStamped gazebo::GazeboRosInterfacePlugin::ros_wrench_stamped_msg_ [private] |
Definition at line 290 of file gazebo_ros_interface_plugin.h.
std::vector<gazebo::transport::SubscriberPtr> gazebo::GazeboRosInterfacePlugin::subscriberPtrs_ [private] |
Definition at line 154 of file gazebo_ros_interface_plugin.h.
Definition at line 330 of file gazebo_ros_interface_plugin.h.
Definition at line 331 of file gazebo_ros_interface_plugin.h.
Pointer to the update event connection.
Definition at line 168 of file gazebo_ros_interface_plugin.h.
physics::WorldPtr gazebo::GazeboRosInterfacePlugin::world_ [private] |
Pointer to the world.
Definition at line 165 of file gazebo_ros_interface_plugin.h.