Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboRosForce Class Reference

#include <gazebo_ros_force.h>

List of all members.

Public Member Functions

 GazeboRosForce ()
 Constructor.
virtual ~GazeboRosForce ()
 Destructor.

Protected Member Functions

void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
virtual void UpdateChild ()

Private Member Functions

void QueueThread ()
 The custom callback queue thread function.
void UpdateObjectForce (const geometry_msgs::Wrench::ConstPtr &_msg)
 call back when a Wrench message is published

Private Attributes

boost::thread callback_queue_thread_
 Thead object for the running callback Thread.
physics::LinkPtr link_
 A pointer to the Link, where force is applied.
std::string link_name_
 The Link this plugin is attached to, and will exert forces on.
boost::mutex lock_
 A mutex to lock access to fields that are used in ROS message callbacks.
ros::CallbackQueue queue_
std::string robot_namespace_
 for setting ROS name space
ros::NodeHandlerosnode_
 A pointer to the ROS node. A node will be instantiated if it does not exist.
ros::Subscriber sub_
std::string topic_name_
 ROS Wrench topic name inputs.
event::ConnectionPtr update_connection_
physics::WorldPtr world_
 A pointer to the gazebo world.
geometry_msgs::Wrench wrench_msg_
 Container for the wrench force that this plugin exerts on the body.

Detailed Description

Definition at line 71 of file gazebo_ros_force.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 35 of file gazebo_ros_force.cpp.

Destructor.

Definition at line 47 of file gazebo_ros_force.cpp.


Member Function Documentation

void gazebo::GazeboRosForce::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
) [protected]

Definition at line 62 of file gazebo_ros_force.cpp.

The custom callback queue thread function.

Definition at line 150 of file gazebo_ros_force.cpp.

void gazebo::GazeboRosForce::UpdateChild ( ) [protected, virtual]

Definition at line 137 of file gazebo_ros_force.cpp.

void gazebo::GazeboRosForce::UpdateObjectForce ( const geometry_msgs::Wrench::ConstPtr &  _msg) [private]

call back when a Wrench message is published

Parameters:
[in]_msgThe Incoming ROS message representing the new force to exert.

Definition at line 125 of file gazebo_ros_force.cpp.


Member Data Documentation

Thead object for the running callback Thread.

Definition at line 116 of file gazebo_ros_force.h.

physics::LinkPtr gazebo::GazeboRosForce::link_ [private]

A pointer to the Link, where force is applied.

Definition at line 96 of file gazebo_ros_force.h.

std::string gazebo::GazeboRosForce::link_name_ [private]

The Link this plugin is attached to, and will exert forces on.

Definition at line 108 of file gazebo_ros_force.h.

boost::mutex gazebo::GazeboRosForce::lock_ [private]

A mutex to lock access to fields that are used in ROS message callbacks.

Definition at line 103 of file gazebo_ros_force.h.

Definition at line 114 of file gazebo_ros_force.h.

for setting ROS name space

Definition at line 111 of file gazebo_ros_force.h.

A pointer to the ROS node. A node will be instantiated if it does not exist.

Definition at line 99 of file gazebo_ros_force.h.

Definition at line 100 of file gazebo_ros_force.h.

std::string gazebo::GazeboRosForce::topic_name_ [private]

ROS Wrench topic name inputs.

Definition at line 106 of file gazebo_ros_force.h.

Definition at line 121 of file gazebo_ros_force.h.

physics::WorldPtr gazebo::GazeboRosForce::world_ [private]

A pointer to the gazebo world.

Definition at line 93 of file gazebo_ros_force.h.

geometry_msgs::Wrench gazebo::GazeboRosForce::wrench_msg_ [private]

Container for the wrench force that this plugin exerts on the body.

Definition at line 118 of file gazebo_ros_force.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Feb 23 2017 03:43:23