This plugin is used to create rosbag files from within gazebo. More...
#include <gazebo_bag_plugin.h>
| Public Member Functions | |
| GazeboBagPlugin () | |
| virtual | ~GazeboBagPlugin () | 
| Protected Member Functions | |
| void | ActuatorsCallback (const mav_msgs::ActuatorsConstPtr &control_msg) | 
| Called when a Actuators message is received. | |
| void | AttitudeThrustCallback (const mav_msgs::AttitudeThrustConstPtr &control_msg) | 
| Called when a AttitudeThrust message is received. | |
| void | CommandPoseCallback (const geometry_msgs::PoseStampedConstPtr &pose_msg) | 
| Called when a PoseStamped message is received. | |
| void | ExternalForceCallback (const geometry_msgs::WrenchStampedConstPtr &force_msg) | 
| Called when an WrenchStamped message is received. | |
| void | ImuCallback (const sensor_msgs::ImuConstPtr &imu_msg) | 
| Called when an IMU message is received. | |
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| Load the plugin. | |
| void | LogGroundTruth (const common::Time now) | 
| Log the ground truth pose and twist. | |
| void | LogMotorVelocities (const common::Time now) | 
| Log all the motor velocities. | |
| void | LogWrenches (const common::Time now) | 
| Log all the wrenches. | |
| void | OnUpdate (const common::UpdateInfo &) | 
| Called when the world is updated. | |
| void | RateThrustCallback (const mav_msgs::RateThrustConstPtr &control_msg) | 
| Called when a RateThrust message is received. | |
| bool | RecordingServiceCallback (rotors_comm::RecordRosbag::Request &req, rotors_comm::RecordRosbag::Response &res) | 
| Called when a request to start or stop recording is received. | |
| void | StartRecording () | 
| Starting recording the rosbag. | |
| void | StopRecording () | 
| Stop recording the rosbag. | |
| void | WaypointCallback (const trajectory_msgs::MultiDOFJointTrajectoryConstPtr &trajectory_msg) | 
| Called when a MultiDOFJointTrajectoryPoint message is received. | |
| void | WindSpeedCallback (const rotors_comm::WindSpeedConstPtr &wind_speed_msg) | 
| Called when a WindSpeed message is received. | |
| Private Types | |
| typedef std::map< const unsigned int, const physics::JointPtr > | MotorNumberToJointMap | 
| typedef std::pair< const unsigned int, const physics::JointPtr > | MotorNumberToJointPair | 
| Private Member Functions | |
| template<class T > | |
| void | writeBag (const std::string &topic, const ros::Time &time, const T &msg) | 
| template<class T > | |
| void | writeBag (const std::string &topic, const ros::Time &time, boost::shared_ptr< T const > const &msg) | 
| Private Attributes | |
| rosbag::Bag | bag_ | 
| std::string | bag_filename_ | 
| physics::Link_V | child_links_ | 
| ros::Subscriber | command_pose_sub_ | 
| std::string | command_pose_topic_ | 
| physics::ContactManager * | contact_mgr_ | 
| Pointer to the ContactManager to get all collisions of this link and its children. | |
| ros::Subscriber | control_attitude_thrust_sub_ | 
| std::string | control_attitude_thrust_topic_ | 
| ros::Subscriber | control_motor_speed_sub_ | 
| std::string | control_motor_speed_topic_ | 
| ros::Subscriber | control_rate_thrust_sub_ | 
| std::string | control_rate_thrust_topic_ | 
| std::ofstream | csvOut | 
| ros::Subscriber | external_force_sub_ | 
| std::string | external_force_topic_ | 
| std::string | frame_id_ | 
| std::string | ground_truth_pose_topic_ | 
| std::string | ground_truth_twist_topic_ | 
| ros::Subscriber | imu_sub_ | 
| std::string | imu_topic_ | 
| bool | is_recording_ | 
| Whether the plugin is currenly recording a rosbag. | |
| physics::LinkPtr | link_ | 
| std::string | link_name_ | 
| physics::ModelPtr | model_ | 
| MotorNumberToJointMap | motor_joints_ | 
| std::string | motor_topic_ | 
| boost::mutex | mtx_ | 
| Mutex lock for thread safety of writing bag files. | |
| std::string | namespace_ | 
| ros::NodeHandle * | node_handle_ | 
| ros::ServiceServer | recording_service_ | 
| std::string | recording_service_name_ | 
| double | rotor_velocity_slowdown_sim_ | 
| event::ConnectionPtr | update_connection_ | 
| Pointer to the update event connection. | |
| bool | wait_to_record_ | 
| Whether the plugin should wait for user command to start recording. | |
| ros::Subscriber | waypoint_sub_ | 
| std::string | waypoint_topic_ | 
| ros::Subscriber | wind_speed_sub_ | 
| std::string | wind_speed_topic_ | 
| physics::WorldPtr | world_ | 
| std::string | wrench_topic_ | 
This plugin is used to create rosbag files from within gazebo.
This plugin is ROS dependent, and is not built if NO_ROS=TRUE is provided to CMakeLists.txt (as in the case of a PX4/Firmware build).
Definition at line 64 of file gazebo_bag_plugin.h.
| typedef std::map<const unsigned int, const physics::JointPtr> gazebo::GazeboBagPlugin::MotorNumberToJointMap  [private] | 
Definition at line 65 of file gazebo_bag_plugin.h.
| typedef std::pair<const unsigned int, const physics::JointPtr> gazebo::GazeboBagPlugin::MotorNumberToJointPair  [private] | 
Definition at line 66 of file gazebo_bag_plugin.h.
| gazebo::GazeboBagPlugin::GazeboBagPlugin | ( | ) |  [inline] | 
Definition at line 68 of file gazebo_bag_plugin.h.
| gazebo::GazeboBagPlugin::~GazeboBagPlugin | ( | ) |  [virtual] | 
Definition at line 30 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::ActuatorsCallback | ( | const mav_msgs::ActuatorsConstPtr & | control_msg | ) |  [protected] | 
Called when a Actuators message is received.
Definition at line 293 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::AttitudeThrustCallback | ( | const mav_msgs::AttitudeThrustConstPtr & | control_msg | ) |  [protected] | 
Called when a AttitudeThrust message is received.
Definition at line 285 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::CommandPoseCallback | ( | const geometry_msgs::PoseStampedConstPtr & | pose_msg | ) |  [protected] | 
Called when a PoseStamped message is received.
| [in] | pose_msg | A PoseStamped message from geometry_msgs. | 
Definition at line 278 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::ExternalForceCallback | ( | const geometry_msgs::WrenchStampedConstPtr & | force_msg | ) |  [protected] | 
Called when an WrenchStamped message is received.
| [in] | force_msg | A WrenchStamped message from geometry_msgs. | 
Definition at line 264 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::ImuCallback | ( | const sensor_msgs::ImuConstPtr & | imu_msg | ) |  [protected] | 
Called when an IMU message is received.
| [in] | imu_msg | A IMU message from sensor_msgs. | 
Definition at line 258 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::Load | ( | physics::ModelPtr | _model, | 
| sdf::ElementPtr | _sdf | ||
| ) |  [protected] | 
Load the plugin.
| [in] | _model | Pointer to the model that loaded this plugin. | 
| [in] | _sdf | SDF element that describes the plugin. | 
Definition at line 39 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::LogGroundTruth | ( | const common::Time | now | ) |  [protected] | 
Log the ground truth pose and twist.
| [in] | now | The current gazebo common::Time | 
Definition at line 332 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::LogMotorVelocities | ( | const common::Time | now | ) |  [protected] | 
Log all the motor velocities.
| [in] | now | The current gazebo common::Time | 
Definition at line 314 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::LogWrenches | ( | const common::Time | now | ) |  [protected] | 
Log all the wrenches.
| [in] | now | The current gazebo common::Time | 
Definition at line 369 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::OnUpdate | ( | const common::UpdateInfo & | _info | ) |  [protected] | 
Called when the world is updated.
| [in] | _info | Update timing information. | 
Definition at line 154 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::RateThrustCallback | ( | const mav_msgs::RateThrustConstPtr & | control_msg | ) |  [protected] | 
Called when a RateThrust message is received.
Definition at line 300 of file gazebo_bag_plugin.cpp.
| bool gazebo::GazeboBagPlugin::RecordingServiceCallback | ( | rotors_comm::RecordRosbag::Request & | req, | 
| rotors_comm::RecordRosbag::Response & | res | ||
| ) |  [protected] | 
Called when a request to start or stop recording is received.
| [in] | req | The request to start or stop recording. | 
| [out] | res | The response to be sent back to the client. | 
Definition at line 398 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::StartRecording | ( | ) |  [protected] | 
Starting recording the rosbag.
Definition at line 166 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::StopRecording | ( | ) |  [protected] | 
Stop recording the rosbag.
Definition at line 235 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::WaypointCallback | ( | const trajectory_msgs::MultiDOFJointTrajectoryConstPtr & | trajectory_msg | ) |  [protected] | 
Called when a MultiDOFJointTrajectoryPoint message is received.
| [in] | trajectory_msg | A MultiDOFJointTrajectoryPoint message from trajectory_msgs. | 
Definition at line 271 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::WindSpeedCallback | ( | const rotors_comm::WindSpeedConstPtr & | wind_speed_msg | ) |  [protected] | 
Called when a WindSpeed message is received.
| [in] | wind_speed_msg | A WindSpeed message from rotors_comm. | 
Definition at line 307 of file gazebo_bag_plugin.cpp.
| void gazebo::GazeboBagPlugin::writeBag | ( | const std::string & | topic, | 
| const ros::Time & | time, | ||
| const T & | msg | ||
| ) |  [inline, private] | 
Definition at line 226 of file gazebo_bag_plugin.h.
| void gazebo::GazeboBagPlugin::writeBag | ( | const std::string & | topic, | 
| const ros::Time & | time, | ||
| boost::shared_ptr< T const > const & | msg | ||
| ) |  [inline, private] | 
Definition at line 245 of file gazebo_bag_plugin.h.
| rosbag::Bag gazebo::GazeboBagPlugin::bag_  [private] | 
Definition at line 207 of file gazebo_bag_plugin.h.
Definition at line 194 of file gazebo_bag_plugin.h.
| physics::Link_V gazebo::GazeboBagPlugin::child_links_  [private] | 
Definition at line 171 of file gazebo_bag_plugin.h.
Definition at line 218 of file gazebo_bag_plugin.h.
Definition at line 185 of file gazebo_bag_plugin.h.
| physics::ContactManager* gazebo::GazeboBagPlugin::contact_mgr_  [private] | 
Pointer to the ContactManager to get all collisions of this link and its children.
Definition at line 177 of file gazebo_bag_plugin.h.
Definition at line 214 of file gazebo_bag_plugin.h.
Definition at line 186 of file gazebo_bag_plugin.h.
Definition at line 215 of file gazebo_bag_plugin.h.
Definition at line 187 of file gazebo_bag_plugin.h.
Definition at line 216 of file gazebo_bag_plugin.h.
Definition at line 188 of file gazebo_bag_plugin.h.
| std::ofstream gazebo::GazeboBagPlugin::csvOut  [private] | 
Definition at line 223 of file gazebo_bag_plugin.h.
Definition at line 212 of file gazebo_bag_plugin.h.
Definition at line 183 of file gazebo_bag_plugin.h.
Definition at line 192 of file gazebo_bag_plugin.h.
Definition at line 180 of file gazebo_bag_plugin.h.
Definition at line 181 of file gazebo_bag_plugin.h.
Definition at line 211 of file gazebo_bag_plugin.h.
Definition at line 182 of file gazebo_bag_plugin.h.
| bool gazebo::GazeboBagPlugin::is_recording_  [private] | 
Whether the plugin is currenly recording a rosbag.
Definition at line 205 of file gazebo_bag_plugin.h.
| physics::LinkPtr gazebo::GazeboBagPlugin::link_  [private] | 
Definition at line 169 of file gazebo_bag_plugin.h.
Definition at line 193 of file gazebo_bag_plugin.h.
| physics::ModelPtr gazebo::GazeboBagPlugin::model_  [private] | 
Definition at line 168 of file gazebo_bag_plugin.h.
Definition at line 173 of file gazebo_bag_plugin.h.
Definition at line 191 of file gazebo_bag_plugin.h.
| boost::mutex gazebo::GazeboBagPlugin::mtx_  [private] | 
Mutex lock for thread safety of writing bag files.
Definition at line 199 of file gazebo_bag_plugin.h.
Definition at line 179 of file gazebo_bag_plugin.h.
Definition at line 208 of file gazebo_bag_plugin.h.
Definition at line 221 of file gazebo_bag_plugin.h.
Definition at line 195 of file gazebo_bag_plugin.h.
| double gazebo::GazeboBagPlugin::rotor_velocity_slowdown_sim_  [private] | 
Definition at line 196 of file gazebo_bag_plugin.h.
Pointer to the update event connection.
Definition at line 165 of file gazebo_bag_plugin.h.
| bool gazebo::GazeboBagPlugin::wait_to_record_  [private] | 
Whether the plugin should wait for user command to start recording.
Definition at line 202 of file gazebo_bag_plugin.h.
Definition at line 213 of file gazebo_bag_plugin.h.
Definition at line 184 of file gazebo_bag_plugin.h.
Definition at line 217 of file gazebo_bag_plugin.h.
Definition at line 189 of file gazebo_bag_plugin.h.
| physics::WorldPtr gazebo::GazeboBagPlugin::world_  [private] | 
Definition at line 167 of file gazebo_bag_plugin.h.
Definition at line 190 of file gazebo_bag_plugin.h.