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

#include <servo_plugin.h>

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

Classes

struct  Servo
 

Public Member Functions

 ServoPlugin ()
 
virtual ~ServoPlugin ()
 

Protected Member Functions

virtual void Init ()
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
virtual void Reset ()
 
virtual void Update ()
 

Private Member Functions

void CalculateVelocities ()
 
void cmdCallback (const geometry_msgs::QuaternionStamped::ConstPtr &cmd_msg)
 
void publish_joint_states ()
 

Private Attributes

common::Time controlPeriod
 
unsigned int countOfServos
 
geometry_msgs::QuaternionStamped::ConstPtr current_cmd
 
float derivativeControllerGain
 
bool enableMotors
 
sensor_msgs::JointState joint_state
 
std::string jointStateName
 
ros::Publisher jointStatePub_
 
float maximumTorque
 
double maximumVelocity
 
boost::mutex mutex
 
unsigned int orderOfAxes [3]
 
common::Time prevUpdateTime
 
float proportionalControllerGain
 
ros::CallbackQueue queue_
 
std::string robotNamespace
 
ros::NodeHandlerosnode_
 
math::Quaternion rotation_
 
unsigned int rotationConv
 
struct gazebo::ServoPlugin::Servo servo [3]
 
ros::Subscriber sub_
 
std::string topicName
 
tf::TransformListenertransform_listener_
 
event::ConnectionPtr updateConnection
 
physics::WorldPtr world
 The parent World. More...
 

Detailed Description

Definition at line 45 of file servo_plugin.h.

Constructor & Destructor Documentation

gazebo::ServoPlugin::ServoPlugin ( )

Definition at line 57 of file servo_plugin.cpp.

gazebo::ServoPlugin::~ServoPlugin ( )
virtual

Definition at line 64 of file servo_plugin.cpp.

Member Function Documentation

void gazebo::ServoPlugin::CalculateVelocities ( )
private

Definition at line 270 of file servo_plugin.cpp.

void gazebo::ServoPlugin::cmdCallback ( const geometry_msgs::QuaternionStamped::ConstPtr &  cmd_msg)
private

Definition at line 459 of file servo_plugin.cpp.

void gazebo::ServoPlugin::Init ( )
protectedvirtual

Definition at line 175 of file servo_plugin.cpp.

void gazebo::ServoPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protectedvirtual

Definition at line 77 of file servo_plugin.cpp.

void gazebo::ServoPlugin::publish_joint_states ( )
private

Definition at line 465 of file servo_plugin.cpp.

void gazebo::ServoPlugin::Reset ( )
protectedvirtual

Definition at line 181 of file servo_plugin.cpp.

void gazebo::ServoPlugin::Update ( )
protectedvirtual

Definition at line 200 of file servo_plugin.cpp.

Member Data Documentation

common::Time gazebo::ServoPlugin::controlPeriod
private

Definition at line 92 of file servo_plugin.h.

unsigned int gazebo::ServoPlugin::countOfServos
private

Definition at line 83 of file servo_plugin.h.

geometry_msgs::QuaternionStamped::ConstPtr gazebo::ServoPlugin::current_cmd
private

Definition at line 114 of file servo_plugin.h.

float gazebo::ServoPlugin::derivativeControllerGain
private

Definition at line 95 of file servo_plugin.h.

bool gazebo::ServoPlugin::enableMotors
private

Definition at line 69 of file servo_plugin.h.

sensor_msgs::JointState gazebo::ServoPlugin::joint_state
private

Definition at line 86 of file servo_plugin.h.

std::string gazebo::ServoPlugin::jointStateName
private

Definition at line 91 of file servo_plugin.h.

ros::Publisher gazebo::ServoPlugin::jointStatePub_
private

Definition at line 101 of file servo_plugin.h.

float gazebo::ServoPlugin::maximumTorque
private

Definition at line 97 of file servo_plugin.h.

double gazebo::ServoPlugin::maximumVelocity
private

Definition at line 96 of file servo_plugin.h.

boost::mutex gazebo::ServoPlugin::mutex
private

Definition at line 113 of file servo_plugin.h.

unsigned int gazebo::ServoPlugin::orderOfAxes[3]
private

Definition at line 84 of file servo_plugin.h.

common::Time gazebo::ServoPlugin::prevUpdateTime
private

Definition at line 67 of file servo_plugin.h.

float gazebo::ServoPlugin::proportionalControllerGain
private

Definition at line 94 of file servo_plugin.h.

ros::CallbackQueue gazebo::ServoPlugin::queue_
private

Definition at line 106 of file servo_plugin.h.

std::string gazebo::ServoPlugin::robotNamespace
private

Definition at line 89 of file servo_plugin.h.

ros::NodeHandle* gazebo::ServoPlugin::rosnode_
private

Definition at line 100 of file servo_plugin.h.

math::Quaternion gazebo::ServoPlugin::rotation_
private

Definition at line 118 of file servo_plugin.h.

unsigned int gazebo::ServoPlugin::rotationConv
private

Definition at line 85 of file servo_plugin.h.

struct gazebo::ServoPlugin::Servo gazebo::ServoPlugin::servo[3]
private
ros::Subscriber gazebo::ServoPlugin::sub_
private

Definition at line 102 of file servo_plugin.h.

std::string gazebo::ServoPlugin::topicName
private

Definition at line 90 of file servo_plugin.h.

tf::TransformListener* gazebo::ServoPlugin::transform_listener_
private

Definition at line 103 of file servo_plugin.h.

event::ConnectionPtr gazebo::ServoPlugin::updateConnection
private

Definition at line 122 of file servo_plugin.h.

physics::WorldPtr gazebo::ServoPlugin::world
private

The parent World.

Definition at line 64 of file servo_plugin.h.


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


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Wed Jun 5 2019 22:40:23