#include <gazebo_ros_joint_trajectory.h>
Public Member Functions | |
GazeboRosJointTrajectory () | |
Constructor. | |
void | Load (physics::WorldPtr _world, sdf::ElementPtr _sdf) |
Load the controller. | |
virtual | ~GazeboRosJointTrajectory () |
Destructor. | |
Private Member Functions | |
void | FixLink (physics::LinkPtr link) |
void | QueueThread () |
void | SetTrajectory (const trajectory_msgs::JointTrajectory::ConstPtr &trajectory) |
Update the controller. | |
bool | SetTrajectory (const gazebo_msgs::SetJointTrajectory::Request &req, const gazebo_msgs::SetJointTrajectory::Response &res) |
void | UnfixLink () |
void | UpdateStates () |
Private Attributes | |
boost::thread | callback_queue_thread_ |
bool | disable_physics_updates_ |
bool | has_trajectory_ |
physics::JointPtr | joint_ |
trajectory_msgs::JointTrajectory | joint_trajectory_ |
common::Time | last_time_ |
save last_time | |
physics::ModelPtr | model_ |
geometry_msgs::Pose | model_pose_ |
bool | physics_engine_enabled_ |
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::NodeHandle * | rosnode_ |
frame transform name, should match link name | |
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_ |
Definition at line 51 of file gazebo_ros_joint_trajectory.h.
Constructor.
Definition at line 38 of file gazebo_ros_joint_trajectory.cpp.
Destructor.
Definition at line 47 of file gazebo_ros_joint_trajectory.cpp.
void gazebo::GazeboRosJointTrajectory::FixLink | ( | physics::LinkPtr | link | ) | [private] |
Definition at line 218 of file gazebo_ros_joint_trajectory.cpp.
void gazebo::GazeboRosJointTrajectory::Load | ( | physics::WorldPtr | _world, |
sdf::ElementPtr | _sdf | ||
) |
Load the controller.
Definition at line 60 of file gazebo_ros_joint_trajectory.cpp.
void gazebo::GazeboRosJointTrajectory::QueueThread | ( | ) | [private] |
Definition at line 337 of file gazebo_ros_joint_trajectory.cpp.
void gazebo::GazeboRosJointTrajectory::SetTrajectory | ( | const trajectory_msgs::JointTrajectory::ConstPtr & | trajectory | ) | [private] |
Update the controller.
Definition at line 141 of file gazebo_ros_joint_trajectory.cpp.
bool gazebo::GazeboRosJointTrajectory::SetTrajectory | ( | const gazebo_msgs::SetJointTrajectory::Request & | req, |
const gazebo_msgs::SetJointTrajectory::Response & | res | ||
) | [private] |
Definition at line 151 of file gazebo_ros_joint_trajectory.cpp.
void gazebo::GazeboRosJointTrajectory::UnfixLink | ( | ) | [private] |
Definition at line 237 of file gazebo_ros_joint_trajectory.cpp.
void gazebo::GazeboRosJointTrajectory::UpdateStates | ( | ) | [private] |
Definition at line 246 of file gazebo_ros_joint_trajectory.cpp.
boost::thread gazebo::GazeboRosJointTrajectory::callback_queue_thread_ [private] |
Definition at line 112 of file gazebo_ros_joint_trajectory.h.
bool gazebo::GazeboRosJointTrajectory::disable_physics_updates_ [private] |
Definition at line 104 of file gazebo_ros_joint_trajectory.h.
bool gazebo::GazeboRosJointTrajectory::has_trajectory_ [private] |
Definition at line 81 of file gazebo_ros_joint_trajectory.h.
physics::JointPtr gazebo::GazeboRosJointTrajectory::joint_ [private] |
Definition at line 121 of file gazebo_ros_joint_trajectory.h.
trajectory_msgs::JointTrajectory gazebo::GazeboRosJointTrajectory::joint_trajectory_ [private] |
Definition at line 117 of file gazebo_ros_joint_trajectory.h.
common::Time gazebo::GazeboRosJointTrajectory::last_time_ [private] |
save last_time
Definition at line 96 of file gazebo_ros_joint_trajectory.h.
physics::ModelPtr gazebo::GazeboRosJointTrajectory::model_ [private] |
Definition at line 69 of file gazebo_ros_joint_trajectory.h.
Definition at line 86 of file gazebo_ros_joint_trajectory.h.
bool gazebo::GazeboRosJointTrajectory::physics_engine_enabled_ [private] |
Definition at line 105 of file gazebo_ros_joint_trajectory.h.
Definition at line 110 of file gazebo_ros_joint_trajectory.h.
physics::LinkPtr gazebo::GazeboRosJointTrajectory::reference_link_ [private] |
pose should be set relative to this link (default to "world")
Definition at line 72 of file gazebo_ros_joint_trajectory.h.
std::string gazebo::GazeboRosJointTrajectory::reference_link_name_ [private] |
Definition at line 73 of file gazebo_ros_joint_trajectory.h.
std::string gazebo::GazeboRosJointTrajectory::robot_namespace_ [private] |
for setting ROS name space
Definition at line 108 of file gazebo_ros_joint_trajectory.h.
frame transform name, should match link name
pointer to ros node
Definition at line 78 of file gazebo_ros_joint_trajectory.h.
std::string gazebo::GazeboRosJointTrajectory::service_name_ [private] |
Definition at line 90 of file gazebo_ros_joint_trajectory.h.
bool gazebo::GazeboRosJointTrajectory::set_model_pose_ [private] |
Definition at line 85 of file gazebo_ros_joint_trajectory.h.
Definition at line 80 of file gazebo_ros_joint_trajectory.h.
Definition at line 79 of file gazebo_ros_joint_trajectory.h.
std::string gazebo::GazeboRosJointTrajectory::topic_name_ [private] |
topic name
Definition at line 89 of file gazebo_ros_joint_trajectory.h.
unsigned int gazebo::GazeboRosJointTrajectory::trajectory_index [private] |
Definition at line 100 of file gazebo_ros_joint_trajectory.h.
trajectory_msgs::JointTrajectory gazebo::GazeboRosJointTrajectory::trajectory_msg_ [private] |
ros message
Definition at line 84 of file gazebo_ros_joint_trajectory.h.
common::Time gazebo::GazeboRosJointTrajectory::trajectory_start [private] |
Definition at line 99 of file gazebo_ros_joint_trajectory.h.
Definition at line 115 of file gazebo_ros_joint_trajectory.h.
boost::mutex gazebo::GazeboRosJointTrajectory::update_mutex [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 93 of file gazebo_ros_joint_trajectory.h.
double gazebo::GazeboRosJointTrajectory::update_rate_ [private] |
Definition at line 103 of file gazebo_ros_joint_trajectory.h.
physics::WorldPtr gazebo::GazeboRosJointTrajectory::world_ [private] |
Definition at line 68 of file gazebo_ros_joint_trajectory.h.