#include <gazebo_ros_joint_pose_trajectory.h>
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::NodeHandle * | rosnode_ |
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_ |
Definition at line 53 of file gazebo_ros_joint_pose_trajectory.h.
ROS_DEPRECATED gazebo::GazeboRosJointPoseTrajectory::GazeboRosJointPoseTrajectory | ( | ) |
Constructor.
Definition at line 36 of file gazebo_ros_joint_pose_trajectory.cpp.
|
virtual |
Destructor.
Definition at line 48 of file gazebo_ros_joint_pose_trajectory.cpp.
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.
|
private |
Definition at line 116 of file gazebo_ros_joint_pose_trajectory.cpp.
|
private |
Definition at line 448 of file gazebo_ros_joint_pose_trajectory.cpp.
|
private |
Update the controller.
Definition at line 165 of file gazebo_ros_joint_pose_trajectory.cpp.
|
private |
Definition at line 338 of file gazebo_ros_joint_pose_trajectory.cpp.
|
private |
Definition at line 117 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 130 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 109 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 85 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 125 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 119 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
save last_time
Definition at line 101 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 75 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 90 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 110 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 120 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 115 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
pose should be set relative to this link (default to "world")
Definition at line 78 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 79 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
for setting ROS name space
Definition at line 113 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
pointer to ros node
Definition at line 82 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 128 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 94 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 89 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 84 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 83 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
topic name
Definition at line 93 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 105 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
ros message
Definition at line 88 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 104 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 123 of file gazebo_ros_joint_pose_trajectory.h.
|
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.
|
private |
Definition at line 108 of file gazebo_ros_joint_pose_trajectory.h.
|
private |
Definition at line 74 of file gazebo_ros_joint_pose_trajectory.h.