Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboControllerInterface Class Reference

#include <gazebo_controller_interface.h>

Inheritance diagram for gazebo::GazeboControllerInterface:
Inheritance graph
[legend]

Public Member Functions

 GazeboControllerInterface ()
 
void InitializeParams ()
 
void Publish ()
 
 ~GazeboControllerInterface ()
 

Protected Member Functions

void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
void OnUpdate (const common::UpdateInfo &)
 

Private Member Functions

void CommandMotorCallback (GzActuatorsMsgPtr &actuators_msg)
 
void CreatePubsAndSubs ()
 Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
 
void QueueThread ()
 

Private Attributes

boost::thread callback_queue_thread_
 
gazebo::transport::SubscriberPtr cmd_motor_sub_
 
std::string command_motor_speed_sub_topic_
 
Eigen::VectorXd input_reference_
 
physics::ModelPtr model_
 
gazebo::transport::PublisherPtr motor_velocity_reference_pub_
 
std::string motor_velocity_reference_pub_topic_
 
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(). More...
 
bool received_first_reference_
 Gets set to true the first time a motor command is received. More...
 
event::ConnectionPtr updateConnection_
 Pointer to the update event connection. More...
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 49 of file gazebo_controller_interface.h.

Constructor & Destructor Documentation

◆ GazeboControllerInterface()

gazebo::GazeboControllerInterface::GazeboControllerInterface ( )
inline

Definition at line 51 of file gazebo_controller_interface.h.

◆ ~GazeboControllerInterface()

gazebo::GazeboControllerInterface::~GazeboControllerInterface ( )

Definition at line 29 of file gazebo_controller_interface.cpp.

Member Function Documentation

◆ CommandMotorCallback()

void gazebo::GazeboControllerInterface::CommandMotorCallback ( GzActuatorsMsgPtr actuators_msg)
private

Definition at line 167 of file gazebo_controller_interface.cpp.

◆ CreatePubsAndSubs()

void gazebo::GazeboControllerInterface::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 104 of file gazebo_controller_interface.cpp.

◆ InitializeParams()

void gazebo::GazeboControllerInterface::InitializeParams ( )

◆ Load()

void gazebo::GazeboControllerInterface::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protected

Definition at line 32 of file gazebo_controller_interface.cpp.

◆ OnUpdate()

void gazebo::GazeboControllerInterface::OnUpdate ( const common::UpdateInfo &  )
protected

Definition at line 73 of file gazebo_controller_interface.cpp.

◆ Publish()

void gazebo::GazeboControllerInterface::Publish ( )

◆ QueueThread()

void gazebo::GazeboControllerInterface::QueueThread ( )
private

Member Data Documentation

◆ callback_queue_thread_

boost::thread gazebo::GazeboControllerInterface::callback_queue_thread_
private

Definition at line 106 of file gazebo_controller_interface.h.

◆ cmd_motor_sub_

gazebo::transport::SubscriberPtr gazebo::GazeboControllerInterface::cmd_motor_sub_
private

Definition at line 98 of file gazebo_controller_interface.h.

◆ command_motor_speed_sub_topic_

std::string gazebo::GazeboControllerInterface::command_motor_speed_sub_topic_
private

Definition at line 93 of file gazebo_controller_interface.h.

◆ input_reference_

Eigen::VectorXd gazebo::GazeboControllerInterface::input_reference_
private

This gets populated (including resizing if needed) when CommandMotorCallback() is called.

Definition at line 88 of file gazebo_controller_interface.h.

◆ model_

physics::ModelPtr gazebo::GazeboControllerInterface::model_
private

Definition at line 100 of file gazebo_controller_interface.h.

◆ motor_velocity_reference_pub_

gazebo::transport::PublisherPtr gazebo::GazeboControllerInterface::motor_velocity_reference_pub_
private

Definition at line 97 of file gazebo_controller_interface.h.

◆ motor_velocity_reference_pub_topic_

std::string gazebo::GazeboControllerInterface::motor_velocity_reference_pub_topic_
private

Definition at line 92 of file gazebo_controller_interface.h.

◆ namespace_

std::string gazebo::GazeboControllerInterface::namespace_
private

Definition at line 91 of file gazebo_controller_interface.h.

◆ node_handle_

gazebo::transport::NodePtr gazebo::GazeboControllerInterface::node_handle_
private

Definition at line 96 of file gazebo_controller_interface.h.

◆ pubs_and_subs_created_

bool gazebo::GazeboControllerInterface::pubs_and_subs_created_
private

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

Definition at line 78 of file gazebo_controller_interface.h.

◆ received_first_reference_

bool gazebo::GazeboControllerInterface::received_first_reference_
private

Gets set to true the first time a motor command is received.

OnUpdate() will not do anything until this is true.

Definition at line 74 of file gazebo_controller_interface.h.

◆ updateConnection_

event::ConnectionPtr gazebo::GazeboControllerInterface::updateConnection_
private

Pointer to the update event connection.

Definition at line 104 of file gazebo_controller_interface.h.

◆ world_

physics::WorldPtr gazebo::GazeboControllerInterface::world_
private

Definition at line 101 of file gazebo_controller_interface.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 Mon Feb 28 2022 23:39:04