This plugin publishes the motor speeds of your multirotor model.
More...
#include <gazebo_multirotor_base_plugin.h>
|
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
| | Load the plugin. More...
|
| |
| void | OnUpdate (const common::UpdateInfo &) |
| | Called when the world is updated. More...
|
| |
|
| void | CreatePubsAndSubs () |
| | Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
|
| |
This plugin publishes the motor speeds of your multirotor model.
Definition at line 48 of file gazebo_multirotor_base_plugin.h.
◆ MotorNumberToJointMap
◆ MotorNumberToJointPair
◆ GazeboMultirotorBasePlugin()
| gazebo::GazeboMultirotorBasePlugin::GazeboMultirotorBasePlugin |
( |
| ) |
|
|
inline |
◆ ~GazeboMultirotorBasePlugin()
| gazebo::GazeboMultirotorBasePlugin::~GazeboMultirotorBasePlugin |
( |
| ) |
|
|
virtual |
◆ CreatePubsAndSubs()
| void gazebo::GazeboMultirotorBasePlugin::CreatePubsAndSubs |
( |
| ) |
|
|
private |
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.
◆ Load()
| void gazebo::GazeboMultirotorBasePlugin::Load |
( |
physics::ModelPtr |
_model, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
protected |
Load the plugin.
- Parameters
-
| [in] | _model | Pointer to the model that loaded this plugin. |
| [in] | _sdf | SDF element that describes the plugin. |
Definition at line 36 of file gazebo_multirotor_base_plugin.cpp.
◆ OnUpdate()
| void gazebo::GazeboMultirotorBasePlugin::OnUpdate |
( |
const common::UpdateInfo & |
_info | ) |
|
|
protected |
◆ actuators_msg_
| gz_sensor_msgs::Actuators gazebo::GazeboMultirotorBasePlugin::actuators_msg_ |
|
private |
◆ actuators_pub_topic_
| std::string gazebo::GazeboMultirotorBasePlugin::actuators_pub_topic_ |
|
private |
◆ child_links_
| physics::Link_V gazebo::GazeboMultirotorBasePlugin::child_links_ |
|
private |
◆ frame_id_
| std::string gazebo::GazeboMultirotorBasePlugin::frame_id_ |
|
private |
◆ joint_state_msg_
| gz_sensor_msgs::JointState gazebo::GazeboMultirotorBasePlugin::joint_state_msg_ |
|
private |
◆ joint_state_pub_
| gazebo::transport::PublisherPtr gazebo::GazeboMultirotorBasePlugin::joint_state_pub_ |
|
private |
◆ joint_state_pub_topic_
| std::string gazebo::GazeboMultirotorBasePlugin::joint_state_pub_topic_ |
|
private |
◆ link_
| physics::LinkPtr gazebo::GazeboMultirotorBasePlugin::link_ |
|
private |
◆ link_name_
| std::string gazebo::GazeboMultirotorBasePlugin::link_name_ |
|
private |
◆ model_
| physics::ModelPtr gazebo::GazeboMultirotorBasePlugin::model_ |
|
private |
◆ motor_joints_
◆ motor_pub_
| gazebo::transport::PublisherPtr gazebo::GazeboMultirotorBasePlugin::motor_pub_ |
|
private |
◆ namespace_
| std::string gazebo::GazeboMultirotorBasePlugin::namespace_ |
|
private |
◆ node_handle_
| gazebo::transport::NodePtr gazebo::GazeboMultirotorBasePlugin::node_handle_ |
|
private |
◆ pubs_and_subs_created_
| bool gazebo::GazeboMultirotorBasePlugin::pubs_and_subs_created_ |
|
private |
◆ rotor_velocity_slowdown_sim_
| double gazebo::GazeboMultirotorBasePlugin::rotor_velocity_slowdown_sim_ |
|
private |
◆ update_connection_
◆ world_
| physics::WorldPtr gazebo::GazeboMultirotorBasePlugin::world_ |
|
private |
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 Mon Feb 28 2022 23:39:04