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

#include <gazebo_ros_joint_pose_trajectory.h>

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

Public Member Functions

 GazeboRosJointPoseTrajectory ()
 Constructor. More...
 
void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Load the controller. More...
 
virtual ~GazeboRosJointPoseTrajectory ()
 Destructor. More...
 

Private Member Functions

void LoadThread ()
 
void QueueThread ()
 
void SetTrajectory (const trajectory_msgs::JointTrajectory::ConstPtr &trajectory)
 Update the controller. More...
 
void UpdateStates ()
 

Private Attributes

boost::thread callback_queue_thread_
 
boost::thread deferred_load_thread_
 
bool disable_physics_updates_
 
bool has_trajectory_
 
trajectory_msgs::JointTrajectory joint_trajectory_
 
std::vector< gazebo::physics::JointPtr > joints_
 
common::Time last_time_
 save last_time More...
 
physics::ModelPtr model_
 
geometry_msgs::Pose model_pose_
 
bool physics_engine_enabled_
 
std::vector< trajectory_msgs::JointTrajectoryPoint > points_
 
ros::CallbackQueue queue_
 
physics::LinkPtr reference_link_
 pose should be set relative to this link (default to "world") More...
 
std::string reference_link_name_
 
std::string robot_namespace_
 for setting ROS name space More...
 
ros::NodeHandlerosnode_
 pointer to ros node More...
 
sdf::ElementPtr sdf
 
std::string service_name_
 
bool set_model_pose_
 
ros::ServiceServer srv_
 
ros::Subscriber sub_
 
std::string topic_name_
 topic name More...
 
unsigned int trajectory_index
 
trajectory_msgs::JointTrajectory trajectory_msg_
 ros message More...
 
common::Time trajectory_start
 
event::ConnectionPtr update_connection_
 
boost::mutex update_mutex
 A mutex to lock access to fields that are used in message callbacks. More...
 
double update_rate_
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 53 of file gazebo_ros_joint_pose_trajectory.h.

Constructor & Destructor Documentation

ROS_DEPRECATED gazebo::GazeboRosJointPoseTrajectory::GazeboRosJointPoseTrajectory ( )

Constructor.

Definition at line 36 of file gazebo_ros_joint_pose_trajectory.cpp.

gazebo::GazeboRosJointPoseTrajectory::~GazeboRosJointPoseTrajectory ( )
virtual

Destructor.

Definition at line 48 of file gazebo_ros_joint_pose_trajectory.cpp.

Member Function Documentation

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

Load the controller.

Definition at line 61 of file gazebo_ros_joint_pose_trajectory.cpp.

void gazebo::GazeboRosJointPoseTrajectory::LoadThread ( )
private

Definition at line 116 of file gazebo_ros_joint_pose_trajectory.cpp.

void gazebo::GazeboRosJointPoseTrajectory::QueueThread ( )
private

Definition at line 444 of file gazebo_ros_joint_pose_trajectory.cpp.

void gazebo::GazeboRosJointPoseTrajectory::SetTrajectory ( const trajectory_msgs::JointTrajectory::ConstPtr &  trajectory)
private

Update the controller.

Definition at line 165 of file gazebo_ros_joint_pose_trajectory.cpp.

void gazebo::GazeboRosJointPoseTrajectory::UpdateStates ( )
private

Definition at line 338 of file gazebo_ros_joint_pose_trajectory.cpp.

Member Data Documentation

boost::thread gazebo::GazeboRosJointPoseTrajectory::callback_queue_thread_
private

Definition at line 117 of file gazebo_ros_joint_pose_trajectory.h.

boost::thread gazebo::GazeboRosJointPoseTrajectory::deferred_load_thread_
private

Definition at line 130 of file gazebo_ros_joint_pose_trajectory.h.

bool gazebo::GazeboRosJointPoseTrajectory::disable_physics_updates_
private

Definition at line 109 of file gazebo_ros_joint_pose_trajectory.h.

bool gazebo::GazeboRosJointPoseTrajectory::has_trajectory_
private

Definition at line 85 of file gazebo_ros_joint_pose_trajectory.h.

trajectory_msgs::JointTrajectory gazebo::GazeboRosJointPoseTrajectory::joint_trajectory_
private

Definition at line 125 of file gazebo_ros_joint_pose_trajectory.h.

std::vector<gazebo::physics::JointPtr> gazebo::GazeboRosJointPoseTrajectory::joints_
private

Definition at line 119 of file gazebo_ros_joint_pose_trajectory.h.

common::Time gazebo::GazeboRosJointPoseTrajectory::last_time_
private

save last_time

Definition at line 101 of file gazebo_ros_joint_pose_trajectory.h.

physics::ModelPtr gazebo::GazeboRosJointPoseTrajectory::model_
private

Definition at line 75 of file gazebo_ros_joint_pose_trajectory.h.

geometry_msgs::Pose gazebo::GazeboRosJointPoseTrajectory::model_pose_
private

Definition at line 90 of file gazebo_ros_joint_pose_trajectory.h.

bool gazebo::GazeboRosJointPoseTrajectory::physics_engine_enabled_
private

Definition at line 110 of file gazebo_ros_joint_pose_trajectory.h.

std::vector<trajectory_msgs::JointTrajectoryPoint> gazebo::GazeboRosJointPoseTrajectory::points_
private

Definition at line 120 of file gazebo_ros_joint_pose_trajectory.h.

ros::CallbackQueue gazebo::GazeboRosJointPoseTrajectory::queue_
private

Definition at line 115 of file gazebo_ros_joint_pose_trajectory.h.

physics::LinkPtr gazebo::GazeboRosJointPoseTrajectory::reference_link_
private

pose should be set relative to this link (default to "world")

Definition at line 78 of file gazebo_ros_joint_pose_trajectory.h.

std::string gazebo::GazeboRosJointPoseTrajectory::reference_link_name_
private

Definition at line 79 of file gazebo_ros_joint_pose_trajectory.h.

std::string gazebo::GazeboRosJointPoseTrajectory::robot_namespace_
private

for setting ROS name space

Definition at line 113 of file gazebo_ros_joint_pose_trajectory.h.

ros::NodeHandle* gazebo::GazeboRosJointPoseTrajectory::rosnode_
private

pointer to ros node

Definition at line 82 of file gazebo_ros_joint_pose_trajectory.h.

sdf::ElementPtr gazebo::GazeboRosJointPoseTrajectory::sdf
private

Definition at line 128 of file gazebo_ros_joint_pose_trajectory.h.

std::string gazebo::GazeboRosJointPoseTrajectory::service_name_
private

Definition at line 94 of file gazebo_ros_joint_pose_trajectory.h.

bool gazebo::GazeboRosJointPoseTrajectory::set_model_pose_
private

Definition at line 89 of file gazebo_ros_joint_pose_trajectory.h.

ros::ServiceServer gazebo::GazeboRosJointPoseTrajectory::srv_
private

Definition at line 84 of file gazebo_ros_joint_pose_trajectory.h.

ros::Subscriber gazebo::GazeboRosJointPoseTrajectory::sub_
private

Definition at line 83 of file gazebo_ros_joint_pose_trajectory.h.

std::string gazebo::GazeboRosJointPoseTrajectory::topic_name_
private

topic name

Definition at line 93 of file gazebo_ros_joint_pose_trajectory.h.

unsigned int gazebo::GazeboRosJointPoseTrajectory::trajectory_index
private

Definition at line 105 of file gazebo_ros_joint_pose_trajectory.h.

trajectory_msgs::JointTrajectory gazebo::GazeboRosJointPoseTrajectory::trajectory_msg_
private

ros message

Definition at line 88 of file gazebo_ros_joint_pose_trajectory.h.

common::Time gazebo::GazeboRosJointPoseTrajectory::trajectory_start
private

Definition at line 104 of file gazebo_ros_joint_pose_trajectory.h.

event::ConnectionPtr gazebo::GazeboRosJointPoseTrajectory::update_connection_
private

Definition at line 123 of file gazebo_ros_joint_pose_trajectory.h.

boost::mutex gazebo::GazeboRosJointPoseTrajectory::update_mutex
private

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

Definition at line 98 of file gazebo_ros_joint_pose_trajectory.h.

double gazebo::GazeboRosJointPoseTrajectory::update_rate_
private

Definition at line 108 of file gazebo_ros_joint_pose_trajectory.h.

physics::WorldPtr gazebo::GazeboRosJointPoseTrajectory::world_
private

Definition at line 74 of file gazebo_ros_joint_pose_trajectory.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27