follow_joint_trajectory_controller_handle.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Unbounded Robotics Inc.
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */
37 
38 #ifndef MOVEIT_PLUGINS_FOLLOW_TRAJECTORY_CONTROLLER_HANDLE
39 #define MOVEIT_PLUGINS_FOLLOW_TRAJECTORY_CONTROLLER_HANDLE
40 
42 #include <control_msgs/FollowJointTrajectoryAction.h>
43 
45 {
46 /*
47  * This is generally used for arms, but could also be used for multi-dof hands,
48  * or anything using a control_mgs/FollowJointTrajectoryAction.
49  */
51  : public ActionBasedControllerHandle<control_msgs::FollowJointTrajectoryAction>
52 {
53 public:
54  FollowJointTrajectoryControllerHandle(const std::string& name, const std::string& action_ns)
55  : ActionBasedControllerHandle<control_msgs::FollowJointTrajectoryAction>(name, action_ns)
56  {
57  }
58 
59  virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& trajectory)
60  {
61  ROS_DEBUG_STREAM_NAMED("FollowJointTrajectoryController", "new trajectory to " << name_);
62 
64  return false;
65 
66  if (!trajectory.multi_dof_joint_trajectory.points.empty())
67  {
68  ROS_WARN_NAMED("FollowJointTrajectoryController", "%s cannot execute multi-dof trajectories.", name_.c_str());
69  }
70 
71  if (done_)
72  ROS_DEBUG_STREAM_NAMED("FollowJointTrajectoryController", "sending trajectory to " << name_);
73  else
74  ROS_DEBUG_STREAM_NAMED("FollowJointTrajectoryController",
75  "sending continuation for the currently executed trajectory to " << name_);
76 
77  control_msgs::FollowJointTrajectoryGoal goal;
78  goal.trajectory = trajectory.joint_trajectory;
79  controller_action_client_->sendGoal(
80  goal, boost::bind(&FollowJointTrajectoryControllerHandle::controllerDoneCallback, this, _1, _2),
83  done_ = false;
85  return true;
86  }
87 
88 protected:
90  const control_msgs::FollowJointTrajectoryResultConstPtr& result)
91  {
92  // Output custom error message for FollowJointTrajectoryResult if necessary
93  if (result)
94  {
95  switch (result->error_code)
96  {
97  case control_msgs::FollowJointTrajectoryResult::INVALID_GOAL:
98  ROS_WARN_STREAM("Controller " << name_ << " failed with error code INVALID_GOAL");
99  break;
100  case control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS:
101  ROS_WARN_STREAM("Controller " << name_ << " failed with error code INVALID_JOINTS");
102  break;
103  case control_msgs::FollowJointTrajectoryResult::OLD_HEADER_TIMESTAMP:
104  ROS_WARN_STREAM("Controller " << name_ << " failed with error code OLD_HEADER_TIMESTAMP");
105  break;
106  case control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED:
107  ROS_WARN_STREAM("Controller " << name_ << " failed with error code PATH_TOLERANCE_VIOLATED");
108  break;
109  case control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED:
110  ROS_WARN_STREAM("Controller " << name_ << " failed with error code GOAL_TOLERANCE_VIOLATED");
111  break;
112  }
113  }
114  else
115  {
116  ROS_WARN_STREAM("Controller " << name_ << ": no result returned");
117  }
118 
120  }
121 
123  {
124  ROS_DEBUG_STREAM_NAMED("FollowJointTrajectoryController", name_ << " started execution");
125  }
126 
127  void controllerFeedbackCallback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr& feedback)
128  {
129  }
130 };
131 
132 } // end namespace moveit_simple_controller_manager
133 
134 #endif // MOVEIT_PLUGINS_FOLLOW_TRAJECTORY_CONTROLLER_HANDLE
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
void controllerFeedbackCallback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
void controllerDoneCallback(const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
#define ROS_WARN_STREAM(args)
FollowJointTrajectoryControllerHandle(const std::string &name, const std::string &action_ns)
std::shared_ptr< actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > > controller_action_client_


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Wed Jul 10 2019 04:04:40