joint_trajectory_controller.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 // Copyright (c) 2008, Willow Garage, Inc.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of PAL Robotics S.L. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 #ifndef JOINT_TRAJECTORY_CONTROLLER_JOINT_TRAJECTORY_CONTROLLER_H
32 #define JOINT_TRAJECTORY_CONTROLLER_JOINT_TRAJECTORY_CONTROLLER_H
33 
34 // C++ standard
35 #include <cassert>
36 #include <iterator>
37 #include <stdexcept>
38 #include <string>
39 
40 // Boost
41 #include <boost/shared_ptr.hpp>
42 #include <boost/scoped_ptr.hpp>
43 #include <boost/dynamic_bitset.hpp>
44 
45 // ROS
46 #include <ros/node_handle.h>
47 
48 // URDF
49 #include <urdf/model.h>
50 
51 // ROS messages
52 #include <control_msgs/FollowJointTrajectoryAction.h>
53 #include <control_msgs/JointTrajectoryControllerState.h>
54 #include <control_msgs/QueryTrajectoryState.h>
55 #include <trajectory_msgs/JointTrajectory.h>
56 
57 // actionlib
59 
60 // realtime_tools
64 
65 // ros_controls
70 
71 // Project
73 
77 
79 {
80 
126 template <class SegmentImpl, class HardwareInterface>
127 class JointTrajectoryController : public controller_interface::Controller<HardwareInterface>
128 {
129 public:
130 
132 
135  bool init(HardwareInterface* hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
136  /*\}*/
137 
141  void starting(const ros::Time& time);
142 
144  void stopping(const ros::Time& /*time*/);
145 
146  void update(const ros::Time& time, const ros::Duration& period);
147  /*\}*/
148 
149 protected:
150 
151  struct TimeData
152  {
153  TimeData() : time(0.0), period(0.0), uptime(0.0) {}
154 
155  ros::Time time;
157  ros::Time uptime;
158  };
159 
165  typedef trajectory_msgs::JointTrajectory::ConstPtr JointTrajectoryConstPtr;
167  typedef boost::scoped_ptr<StatePublisher> StatePublisherPtr;
168 
169  typedef JointTrajectorySegment<SegmentImpl> Segment;
170  typedef std::vector<Segment> TrajectoryPerJoint;
171  typedef std::vector<TrajectoryPerJoint> Trajectory;
175  typedef typename Segment::Scalar Scalar;
176 
178  typedef typename HardwareInterface::ResourceHandleType JointHandle;
179 
180  bool verbose_;
181  std::string name_;
182  std::vector<JointHandle> joints_;
183  std::vector<bool> angle_wraparound_;
184  std::vector<std::string> joint_names_;
185  SegmentTolerances<Scalar> default_tolerances_;
186  HwIfaceAdapter hw_iface_adapter_;
187 
188  RealtimeGoalHandlePtr rt_active_goal_;
189 
197  TrajectoryBox curr_trajectory_box_;
198  TrajectoryPtr hold_trajectory_ptr_;
199 
200  typename Segment::State current_state_;
201  typename Segment::State desired_state_;
202  typename Segment::State state_error_;
203  typename Segment::State desired_joint_state_;
204  typename Segment::State state_joint_error_;
205 
207 
210 
212  boost::dynamic_bitset<> successful_joint_traj_;
214 
215  // ROS API
218  ActionServerPtr action_server_;
220  StatePublisherPtr state_publisher_;
221 
224 
225  // Mimic Joints
226  std::vector<JointHandle> mimic_joints_;
227  std::vector<std::string> mimic_joint_names_;
228  std::vector<urdf::JointConstSharedPtr> mimic_urdf_joints_;
229  std::vector<unsigned int> mimic_joint_ids_;
230 
231  typename Segment::State mimic_current_state_;
232  typename Segment::State mimic_desired_state_;
233  typename Segment::State mimic_state_error_;
234  HwIfaceAdapter mimic_hw_iface_adapter_;
235 
236  virtual bool updateTrajectoryCommand(const JointTrajectoryConstPtr& msg, RealtimeGoalHandlePtr gh, std::string* error_string = 0);
237  virtual void trajectoryCommandCB(const JointTrajectoryConstPtr& msg);
238  virtual void goalCB(GoalHandle gh);
239  virtual void cancelCB(GoalHandle gh);
240  virtual void preemptActiveGoal();
241  virtual bool queryStateService(control_msgs::QueryTrajectoryState::Request& req,
242  control_msgs::QueryTrajectoryState::Response& resp);
243 
249  void publishState(const ros::Time& time);
250 
259  void setHoldPosition(const ros::Time& time, RealtimeGoalHandlePtr gh=RealtimeGoalHandlePtr());
260 
261 };
262 
263 } // namespace
264 
266 #endif // header guard
Segment::State current_state_
Preallocated workspace variable.
boost::scoped_ptr< StatePublisher > StatePublisherPtr
ServerGoalHandle< ActionSpec > GoalHandle
Segment::State state_error_
Preallocated workspace variable.
HwIfaceAdapter hw_iface_adapter_
Adapts desired trajectory state to HW interface.
Segment::State desired_joint_state_
Preallocated workspace variable.
Controller for executing joint-space trajectories on a group of joints.
trajectory_msgs::JointTrajectory::ConstPtr JointTrajectoryConstPtr
boost::shared_ptr< ActionServer > ActionServerPtr
HardwareInterface::ResourceHandleType JointHandle
std::vector< TrajectoryPerJoint > Trajectory
Segment::State desired_state_
Preallocated workspace variable.
Segment::Time stop_trajectory_duration_
Duration for stop ramp. If zero, the controller stops at the actual position.
boost::shared_ptr< RealtimeGoalHandle > RealtimeGoalHandlePtr
JointTrajectorySegment< SegmentImpl > Segment
void update(const ros::Time &time, const ros::Duration &period)
bool verbose_
Hard coded verbose flag to help in debugging.
realtime_tools::RealtimeServerGoalHandle< control_msgs::FollowJointTrajectoryAction > RealtimeGoalHandle
boost::shared_ptr< TrajectoryPerJoint > TrajectoryPerJointPtr
virtual void trajectoryCommandCB(const JointTrajectoryConstPtr &msg)
realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > StatePublisher
void setHoldPosition(const ros::Time &time, RealtimeGoalHandlePtr gh=RealtimeGoalHandlePtr())
std::vector< JointHandle > joints_
Handles to controlled joints.
RealtimeGoalHandlePtr rt_active_goal_
Currently active action goal, if any.
bool init(HardwareInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
TrajectoryPtr hold_trajectory_ptr_
Last hold trajectory values.
Segment::State state_joint_error_
Preallocated workspace variable.
ros::Time uptime
Controller uptime. Set to zero at every restart.
HardwareInterfaceAdapter< HardwareInterface, typename Segment::State > HwIfaceAdapter
virtual bool updateTrajectoryCommand(const JointTrajectoryConstPtr &msg, RealtimeGoalHandlePtr gh, std::string *error_string=0)
virtual bool queryStateService(control_msgs::QueryTrajectoryState::Request &req, control_msgs::QueryTrajectoryState::Response &resp)
SegmentTolerances< Scalar > default_tolerances_
Default trajectory segment tolerances.
std::vector< std::string > joint_names_
Controlled joint names.
realtime_tools::RealtimeBox< TrajectoryPtr > TrajectoryBox
std::vector< bool > angle_wraparound_
Whether controlled joints wrap around or not.
actionlib::ActionServer< control_msgs::FollowJointTrajectoryAction > ActionServer


gundam_rx78_control
Author(s): Kei Okada , Naoki Hiraoka
autogenerated on Wed Sep 2 2020 03:33:33