Public Member Functions | Private Member Functions | Private Attributes
gazebo::GazeboRosJointTrajectory Class Reference

#include <gazebo_ros_joint_trajectory.h>

List of all members.

Public Member Functions

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

Private Member Functions

void LoadThread ()
void QueueThread ()
void SetTrajectory (const trajectory_msgs::JointTrajectory::ConstPtr &trajectory)
 Update the controller.
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
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")
std::string reference_link_name_
std::string robot_namespace_
 for setting ROS name space
ros::NodeHandlerosnode_
 pointer to ros node
sdf::ElementPtr sdf
std::string service_name_
bool set_model_pose_
ros::ServiceServer srv_
ros::Subscriber sub_
std::string topic_name_
 topic name
unsigned int trajectory_index
trajectory_msgs::JointTrajectory trajectory_msg_
 ros message
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.
double update_rate_
physics::WorldPtr world_

Detailed Description

Definition at line 53 of file gazebo_ros_joint_trajectory.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 36 of file gazebo_ros_joint_trajectory.cpp.

Destructor.

Definition at line 49 of file gazebo_ros_joint_trajectory.cpp.


Member Function Documentation

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

Load the controller.

Definition at line 62 of file gazebo_ros_joint_trajectory.cpp.

Definition at line 118 of file gazebo_ros_joint_trajectory.cpp.

Definition at line 397 of file gazebo_ros_joint_trajectory.cpp.

void gazebo::GazeboRosJointTrajectory::SetTrajectory ( const trajectory_msgs::JointTrajectory::ConstPtr &  trajectory) [private]

Update the controller.

Definition at line 163 of file gazebo_ros_joint_trajectory.cpp.

Definition at line 310 of file gazebo_ros_joint_trajectory.cpp.


Member Data Documentation

Definition at line 117 of file gazebo_ros_joint_trajectory.h.

Definition at line 130 of file gazebo_ros_joint_trajectory.h.

Definition at line 109 of file gazebo_ros_joint_trajectory.h.

Definition at line 85 of file gazebo_ros_joint_trajectory.h.

trajectory_msgs::JointTrajectory gazebo::GazeboRosJointTrajectory::joint_trajectory_ [private]

Definition at line 125 of file gazebo_ros_joint_trajectory.h.

std::vector<gazebo::physics::JointPtr> gazebo::GazeboRosJointTrajectory::joints_ [private]

Definition at line 119 of file gazebo_ros_joint_trajectory.h.

save last_time

Definition at line 101 of file gazebo_ros_joint_trajectory.h.

physics::ModelPtr gazebo::GazeboRosJointTrajectory::model_ [private]

Definition at line 75 of file gazebo_ros_joint_trajectory.h.

Definition at line 90 of file gazebo_ros_joint_trajectory.h.

Definition at line 110 of file gazebo_ros_joint_trajectory.h.

std::vector<trajectory_msgs::JointTrajectoryPoint> gazebo::GazeboRosJointTrajectory::points_ [private]

Definition at line 120 of file gazebo_ros_joint_trajectory.h.

Definition at line 115 of file gazebo_ros_joint_trajectory.h.

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

Definition at line 78 of file gazebo_ros_joint_trajectory.h.

Definition at line 79 of file gazebo_ros_joint_trajectory.h.

for setting ROS name space

Definition at line 113 of file gazebo_ros_joint_trajectory.h.

pointer to ros node

Definition at line 82 of file gazebo_ros_joint_trajectory.h.

sdf::ElementPtr gazebo::GazeboRosJointTrajectory::sdf [private]

Definition at line 128 of file gazebo_ros_joint_trajectory.h.

Definition at line 94 of file gazebo_ros_joint_trajectory.h.

Definition at line 89 of file gazebo_ros_joint_trajectory.h.

Definition at line 84 of file gazebo_ros_joint_trajectory.h.

Definition at line 83 of file gazebo_ros_joint_trajectory.h.

topic name

Definition at line 93 of file gazebo_ros_joint_trajectory.h.

Definition at line 105 of file gazebo_ros_joint_trajectory.h.

trajectory_msgs::JointTrajectory gazebo::GazeboRosJointTrajectory::trajectory_msg_ [private]

ros message

Definition at line 88 of file gazebo_ros_joint_trajectory.h.

Definition at line 104 of file gazebo_ros_joint_trajectory.h.

Definition at line 123 of file gazebo_ros_joint_trajectory.h.

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

Definition at line 98 of file gazebo_ros_joint_trajectory.h.

Definition at line 108 of file gazebo_ros_joint_trajectory.h.

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

Definition at line 74 of file gazebo_ros_joint_trajectory.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:10