gazebo_ros_joint_pose_trajectory.h
Go to the documentation of this file.
1 /*
2  * Copyright 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 // *************************************************************
19 // DEPRECATED
20 // This class has been renamed to gazebo_ros_joint_pose_trajectory
21 // *************************************************************
22 
23 #ifndef GAZEBO_ROS_JOINT_TRAJECTORY_PLUGIN_HH
24 #define GAZEBO_ROS_JOINT_TRAJECTORY_PLUGIN_HH
25 
26 #include <string>
27 #include <vector>
28 
29 #include <boost/thread.hpp>
30 #include <boost/thread/mutex.hpp>
31 
32 #include <ros/ros.h>
33 #include <ros/callback_queue.h>
34 #include <ros/advertise_options.h>
35 #include <ros/subscribe_options.h>
36 
37 #include <trajectory_msgs/JointTrajectory.h>
38 #include <geometry_msgs/Pose.h>
39 
40 #undef ENABLE_SERVICE
41 #ifdef ENABLE_SERVICE
42 #include <gazebo_msgs/SetJointTrajectory.h>
43 #endif
44 
45 #include <gazebo/physics/physics.hh>
46 #include <gazebo/transport/TransportTypes.hh>
47 #include <gazebo/common/Time.hh>
48 #include <gazebo/common/Plugin.hh>
49 #include <gazebo/common/Events.hh>
50 
51 namespace gazebo
52 {
53  class GazeboRosJointPoseTrajectory : public ModelPlugin // replaced with GazeboROSJointPoseTrajectory
54  {
57 
59  public: virtual ~GazeboRosJointPoseTrajectory();
60 
62  public: void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
63 
65  private: void SetTrajectory(
66  const trajectory_msgs::JointTrajectory::ConstPtr& trajectory);
67 #ifdef ENABLE_SERVICE
68  private: bool SetTrajectory(
69  const gazebo_msgs::SetJointTrajectory::Request& req,
70  const gazebo_msgs::SetJointTrajectory::Response& res);
71 #endif
72  private: void UpdateStates();
73 
74  private: physics::WorldPtr world_;
75  private: physics::ModelPtr model_;
76 
78  private: physics::LinkPtr reference_link_;
79  private: std::string reference_link_name_;
80 
85  private: bool has_trajectory_;
86 
88  private: trajectory_msgs::JointTrajectory trajectory_msg_;
89  private: bool set_model_pose_;
90  private: geometry_msgs::Pose model_pose_;
91 
93  private: std::string topic_name_;
94  private: std::string service_name_;
95 
98  private: boost::mutex update_mutex;
99 
101  private: common::Time last_time_;
102 
103  // trajectory time control
104  private: common::Time trajectory_start;
105  private: unsigned int trajectory_index;
106 
107  // rate control
108  private: double update_rate_;
110  private: bool physics_engine_enabled_;
111 
113  private: std::string robot_namespace_;
114 
116  private: void QueueThread();
117  private: boost::thread callback_queue_thread_;
118 
119  private: std::vector<gazebo::physics::JointPtr> joints_;
120  private: std::vector<trajectory_msgs::JointTrajectoryPoint> points_;
121 
122  // Pointer to the update event connection
123  private: event::ConnectionPtr update_connection_;
124 
125  private: trajectory_msgs::JointTrajectory joint_trajectory_;
126 
127  // deferred load in case ros is blocking
128  private: sdf::ElementPtr sdf;
129  private: void LoadThread();
130  private: boost::thread deferred_load_thread_;
131  };
132 }
133 #endif
gazebo::GazeboRosJointPoseTrajectory::update_connection_
event::ConnectionPtr update_connection_
Definition: gazebo_ros_joint_pose_trajectory.h:123
gazebo::GazeboRosJointPoseTrajectory::model_
physics::ModelPtr model_
Definition: gazebo_ros_joint_pose_trajectory.h:75
gazebo
gazebo::GazeboRosJointPoseTrajectory::queue_
ros::CallbackQueue queue_
Definition: gazebo_ros_joint_pose_trajectory.h:115
gazebo::GazeboRosJointPoseTrajectory::joints_
std::vector< gazebo::physics::JointPtr > joints_
Definition: gazebo_ros_joint_pose_trajectory.h:119
ros.h
gazebo::GazeboRosJointPoseTrajectory::disable_physics_updates_
bool disable_physics_updates_
Definition: gazebo_ros_joint_pose_trajectory.h:109
gazebo::GazeboRosJointPoseTrajectory::sub_
ros::Subscriber sub_
Definition: gazebo_ros_joint_pose_trajectory.h:83
gazebo::GazeboRosJointPoseTrajectory::service_name_
std::string service_name_
Definition: gazebo_ros_joint_pose_trajectory.h:94
gazebo::GazeboRosJointPoseTrajectory::physics_engine_enabled_
bool physics_engine_enabled_
Definition: gazebo_ros_joint_pose_trajectory.h:110
gazebo::GazeboRosJointPoseTrajectory::rosnode_
ros::NodeHandle * rosnode_
pointer to ros node
Definition: gazebo_ros_joint_pose_trajectory.h:82
ros::ServiceServer
gazebo::GazeboRosJointPoseTrajectory::set_model_pose_
bool set_model_pose_
Definition: gazebo_ros_joint_pose_trajectory.h:89
gazebo::GazeboRosJointPoseTrajectory::callback_queue_thread_
boost::thread callback_queue_thread_
Definition: gazebo_ros_joint_pose_trajectory.h:117
ros::CallbackQueue
gazebo::GazeboRosJointPoseTrajectory::SetTrajectory
void SetTrajectory(const trajectory_msgs::JointTrajectory::ConstPtr &trajectory)
Update the controller.
Definition: gazebo_ros_joint_pose_trajectory.cpp:169
gazebo::GazeboRosJointPoseTrajectory::GazeboRosJointPoseTrajectory
GazeboRosJointPoseTrajectory()
Constructor.
Definition: gazebo_ros_joint_pose_trajectory.cpp:40
gazebo::GazeboRosJointPoseTrajectory::joint_trajectory_
trajectory_msgs::JointTrajectory joint_trajectory_
Definition: gazebo_ros_joint_pose_trajectory.h:125
gazebo::GazeboRosJointPoseTrajectory::srv_
ros::ServiceServer srv_
Definition: gazebo_ros_joint_pose_trajectory.h:84
gazebo::GazeboRosJointPoseTrajectory::topic_name_
std::string topic_name_
topic name
Definition: gazebo_ros_joint_pose_trajectory.h:93
gazebo::GazeboRosJointPoseTrajectory::model_pose_
geometry_msgs::Pose model_pose_
Definition: gazebo_ros_joint_pose_trajectory.h:90
gazebo::GazeboRosJointPoseTrajectory::trajectory_index
unsigned int trajectory_index
Definition: gazebo_ros_joint_pose_trajectory.h:105
gazebo::GazeboRosJointPoseTrajectory::QueueThread
void QueueThread()
Definition: gazebo_ros_joint_pose_trajectory.cpp:456
gazebo::GazeboRosJointPoseTrajectory::update_rate_
double update_rate_
Definition: gazebo_ros_joint_pose_trajectory.h:108
gazebo::GazeboRosJointPoseTrajectory::LoadThread
void LoadThread()
Definition: gazebo_ros_joint_pose_trajectory.cpp:120
gazebo::GazeboRosJointPoseTrajectory::has_trajectory_
bool has_trajectory_
Definition: gazebo_ros_joint_pose_trajectory.h:85
gazebo::GazeboRosJointPoseTrajectory::sdf
sdf::ElementPtr sdf
Definition: gazebo_ros_joint_pose_trajectory.h:128
gazebo::GazeboRosJointPoseTrajectory::Load
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load the controller.
Definition: gazebo_ros_joint_pose_trajectory.cpp:65
callback_queue.h
advertise_options.h
gazebo::GazeboRosJointPoseTrajectory
Definition: gazebo_ros_joint_pose_trajectory.h:53
gazebo::GazeboRosJointPoseTrajectory::robot_namespace_
std::string robot_namespace_
for setting ROS name space
Definition: gazebo_ros_joint_pose_trajectory.h:113
gazebo::GazeboRosJointPoseTrajectory::world_
physics::WorldPtr world_
Definition: gazebo_ros_joint_pose_trajectory.h:74
gazebo::GazeboRosJointPoseTrajectory::deferred_load_thread_
boost::thread deferred_load_thread_
Definition: gazebo_ros_joint_pose_trajectory.h:130
gazebo::GazeboRosJointPoseTrajectory::reference_link_
physics::LinkPtr reference_link_
pose should be set relative to this link (default to "world")
Definition: gazebo_ros_joint_pose_trajectory.h:78
gazebo::GazeboRosJointPoseTrajectory::~GazeboRosJointPoseTrajectory
virtual ~GazeboRosJointPoseTrajectory()
Destructor.
Definition: gazebo_ros_joint_pose_trajectory.cpp:52
gazebo::GazeboRosJointPoseTrajectory::trajectory_start
common::Time trajectory_start
Definition: gazebo_ros_joint_pose_trajectory.h:104
gazebo::GazeboRosJointPoseTrajectory::update_mutex
boost::mutex update_mutex
A mutex to lock access to fields that are used in message callbacks.
Definition: gazebo_ros_joint_pose_trajectory.h:98
gazebo::GazeboRosJointPoseTrajectory::trajectory_msg_
trajectory_msgs::JointTrajectory trajectory_msg_
ros message
Definition: gazebo_ros_joint_pose_trajectory.h:88
gazebo::GazeboRosJointPoseTrajectory::last_time_
common::Time last_time_
save last_time
Definition: gazebo_ros_joint_pose_trajectory.h:101
gazebo::GazeboRosJointPoseTrajectory::points_
std::vector< trajectory_msgs::JointTrajectoryPoint > points_
Definition: gazebo_ros_joint_pose_trajectory.h:120
gazebo::GazeboRosJointPoseTrajectory::reference_link_name_
std::string reference_link_name_
Definition: gazebo_ros_joint_pose_trajectory.h:79
subscribe_options.h
gazebo::GazeboRosJointPoseTrajectory::UpdateStates
void UpdateStates()
Definition: gazebo_ros_joint_pose_trajectory.cpp:342
ros::NodeHandle
ros::Subscriber


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55