Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
gazebo::GazeboMultirotorBasePlugin Class Reference

This plugin publishes the motor speeds of your multirotor model. More...

#include <gazebo_multirotor_base_plugin.h>

List of all members.

Public Member Functions

 GazeboMultirotorBasePlugin ()
virtual ~GazeboMultirotorBasePlugin ()

Protected Member Functions

void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Load the plugin.
void OnUpdate (const common::UpdateInfo &)
 Called when the world is updated.

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

void CreatePubsAndSubs ()
 Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.

Private Attributes

gz_sensor_msgs::Actuators actuators_msg_
std::string actuators_pub_topic_
physics::Link_V child_links_
std::string frame_id_
gz_sensor_msgs::JointState joint_state_msg_
gazebo::transport::PublisherPtr joint_state_pub_
std::string joint_state_pub_topic_
physics::LinkPtr link_
std::string link_name_
physics::ModelPtr model_
MotorNumberToJointMap motor_joints_
gazebo::transport::PublisherPtr motor_pub_
std::string namespace_
gazebo::transport::NodePtr node_handle_
bool pubs_and_subs_created_
 Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().
double rotor_velocity_slowdown_sim_
event::ConnectionPtr update_connection_
 Pointer to the update event connection.
physics::WorldPtr world_

Detailed Description

This plugin publishes the motor speeds of your multirotor model.

Definition at line 48 of file gazebo_multirotor_base_plugin.h.


Member Typedef Documentation

typedef std::map<const unsigned int, const physics::JointPtr> gazebo::GazeboMultirotorBasePlugin::MotorNumberToJointMap [private]

Definition at line 49 of file gazebo_multirotor_base_plugin.h.

typedef std::pair<const unsigned int, const physics::JointPtr> gazebo::GazeboMultirotorBasePlugin::MotorNumberToJointPair [private]

Definition at line 50 of file gazebo_multirotor_base_plugin.h.


Constructor & Destructor Documentation

Definition at line 52 of file gazebo_multirotor_base_plugin.h.

Definition at line 32 of file gazebo_multirotor_base_plugin.cpp.


Member Function Documentation

Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.

Call this once the first time OnUpdate() is called (can't be called from Load() because there is no guarantee GazeboRosInterfacePlugin has has loaded and listening to ConnectGazeboToRosTopic and ConnectRosToGazeboTopic messages).

Definition at line 130 of file gazebo_multirotor_base_plugin.cpp.

void gazebo::GazeboMultirotorBasePlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
) [protected]

Load the plugin.

Parameters:
[in]_modelPointer to the model that loaded this plugin.
[in]_sdfSDF element that describes the plugin.

Definition at line 36 of file gazebo_multirotor_base_plugin.cpp.

void gazebo::GazeboMultirotorBasePlugin::OnUpdate ( const common::UpdateInfo &  _info) [protected]

Called when the world is updated.

Parameters:
[in]_infoUpdate timing information.

Definition at line 89 of file gazebo_multirotor_base_plugin.cpp.


Member Data Documentation

gz_sensor_msgs::Actuators gazebo::GazeboMultirotorBasePlugin::actuators_msg_ [private]

Re-used message object, defined here to reduce dynamic memory allocation.

Definition at line 109 of file gazebo_multirotor_base_plugin.h.

Definition at line 101 of file gazebo_multirotor_base_plugin.h.

Definition at line 95 of file gazebo_multirotor_base_plugin.h.

Definition at line 103 of file gazebo_multirotor_base_plugin.h.

gz_sensor_msgs::JointState gazebo::GazeboMultirotorBasePlugin::joint_state_msg_ [private]

Re-used message object, defined here to reduce dynamic memory allocation.

Definition at line 114 of file gazebo_multirotor_base_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboMultirotorBasePlugin::joint_state_pub_ [private]

Definition at line 111 of file gazebo_multirotor_base_plugin.h.

Definition at line 100 of file gazebo_multirotor_base_plugin.h.

physics::LinkPtr gazebo::GazeboMultirotorBasePlugin::link_ [private]

Definition at line 93 of file gazebo_multirotor_base_plugin.h.

Definition at line 102 of file gazebo_multirotor_base_plugin.h.

physics::ModelPtr gazebo::GazeboMultirotorBasePlugin::model_ [private]

Definition at line 92 of file gazebo_multirotor_base_plugin.h.

Definition at line 97 of file gazebo_multirotor_base_plugin.h.

gazebo::transport::PublisherPtr gazebo::GazeboMultirotorBasePlugin::motor_pub_ [private]

Definition at line 106 of file gazebo_multirotor_base_plugin.h.

Definition at line 99 of file gazebo_multirotor_base_plugin.h.

gazebo::transport::NodePtr gazebo::GazeboMultirotorBasePlugin::node_handle_ [private]

Definition at line 116 of file gazebo_multirotor_base_plugin.h.

Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().

Definition at line 80 of file gazebo_multirotor_base_plugin.h.

Definition at line 104 of file gazebo_multirotor_base_plugin.h.

Pointer to the update event connection.

Definition at line 89 of file gazebo_multirotor_base_plugin.h.

physics::WorldPtr gazebo::GazeboMultirotorBasePlugin::world_ [private]

Definition at line 91 of file gazebo_multirotor_base_plugin.h.


The documentation for this class was generated from the following files:


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:43