23 #ifndef ROTORS_GAZEBO_PLUGINS_CONTROLLER_INTERFACE_H 24 #define ROTORS_GAZEBO_PLUGINS_CONTROLLER_INTERFACE_H 26 #include <boost/bind.hpp> 27 #include <Eigen/Eigen> 30 #include <gazebo/common/Plugin.hh> 31 #include <gazebo/gazebo.hh> 32 #include <gazebo/physics/physics.hh> 36 #include "Actuators.pb.h" 67 void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
68 void OnUpdate(
const common::UpdateInfo& );
116 #endif // ROTORS_GAZEBO_PLUGINS_CONTROLLER_INTERFACE_H
void CommandMotorCallback(GzActuatorsMsgPtr &actuators_msg)
Eigen::VectorXd input_reference_
gazebo::transport::SubscriberPtr cmd_motor_sub_
const boost::shared_ptr< const gz_sensor_msgs::Actuators > GzActuatorsMsgPtr
static const std::string kDefaultNamespace
event::ConnectionPtr updateConnection_
Pointer to the update event connection.
static const std::string kDefaultMotorVelocityReferenceTopic
Motor speed topic name.
~GazeboControllerInterface()
gazebo::transport::NodePtr node_handle_
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
bool pubs_and_subs_created_
Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from...
gazebo::transport::PublisherPtr motor_velocity_reference_pub_
void CreatePubsAndSubs()
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required...
GazeboControllerInterface()
void OnUpdate(const common::UpdateInfo &)
std::string command_motor_speed_sub_topic_
bool received_first_reference_
Gets set to true the first time a motor command is received.
boost::thread callback_queue_thread_
std::string motor_velocity_reference_pub_topic_