23 #ifndef ROTORS_GAZEBO_PLUGINS_GAZEBO_MULTIROTOR_BASE_PLUGIN_H 24 #define ROTORS_GAZEBO_PLUGINS_GAZEBO_MULTIROTOR_BASE_PLUGIN_H 28 #include <gazebo/common/common.hh> 29 #include <gazebo/common/Plugin.hh> 30 #include <gazebo/gazebo.hh> 31 #include <gazebo/physics/physics.hh> 35 #include "Actuators.pb.h" 36 #include "JointState.pb.h" 70 void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
74 void OnUpdate(
const common::UpdateInfo& );
121 #endif // ROTORS_GAZEBO_PLUGINS_GAZEBO_MULTIROTOR_BASE_PLUGIN_H void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the plugin.
static const std::string kDefaultFrameId
static constexpr double kDefaultRotorVelocitySlowdownSim
GazeboMultirotorBasePlugin()
static const std::string kDefaultLinkName
gz_sensor_msgs::Actuators actuators_msg_
This plugin publishes the motor speeds of your multirotor model.
virtual ~GazeboMultirotorBasePlugin()
static const std::string kDefaultJointStatePubTopic
std::string joint_state_pub_topic_
MotorNumberToJointMap motor_joints_
event::ConnectionPtr update_connection_
Pointer to the update event connection.
gazebo::transport::NodePtr node_handle_
void CreatePubsAndSubs()
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required...
gazebo::transport::PublisherPtr joint_state_pub_
std::string actuators_pub_topic_
static const std::string kDefaultNamespace
bool pubs_and_subs_created_
Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from...
double rotor_velocity_slowdown_sim_
std::pair< const unsigned int, const physics::JointPtr > MotorNumberToJointPair
physics::Link_V child_links_
std::map< const unsigned int, const physics::JointPtr > MotorNumberToJointMap
gazebo::transport::PublisherPtr motor_pub_
void OnUpdate(const common::UpdateInfo &)
Called when the world is updated.
gz_sensor_msgs::JointState joint_state_msg_