moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
follow_joint_trajectory_controller_handle.cpp
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
39
40using namespace std::placeholders;
41
43{
44bool FollowJointTrajectoryControllerHandle::sendTrajectory(const moveit_msgs::msg::RobotTrajectory& trajectory)
45{
46 RCLCPP_DEBUG_STREAM(logger_, "new trajectory to " << name_);
47
49 return false;
50
51 if (!isConnected())
52 {
53 RCLCPP_ERROR_STREAM(logger_, "Action client not connected to action server: " << getActionName());
54 return false;
55 }
56
57 if (done_)
58 {
59 RCLCPP_INFO_STREAM(logger_, "sending trajectory to " << name_);
60 }
61 else
62 {
63 RCLCPP_INFO_STREAM(logger_, "sending continuation for the currently executed trajectory to " << name_);
64 }
65
66 control_msgs::action::FollowJointTrajectory::Goal goal = goal_template_;
67 goal.trajectory = trajectory.joint_trajectory;
68 goal.multi_dof_trajectory = trajectory.multi_dof_joint_trajectory;
69
70 rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::SendGoalOptions send_goal_options;
71 // Active callback
72 send_goal_options.goal_response_callback =
73 [this](
74 const rclcpp_action::Client<control_msgs::action::FollowJointTrajectory>::GoalHandle::SharedPtr& goal_handle) {
75 RCLCPP_INFO_STREAM(logger_, name_ << " started execution");
76 if (!goal_handle)
77 {
78 RCLCPP_WARN(logger_, "Goal request rejected");
79 }
80 else
81 {
82 RCLCPP_INFO(logger_, "Goal request accepted!");
83 }
84 };
85
86 done_ = false;
88
89 // Send goal
90 auto current_goal_future = controller_action_client_->async_send_goal(goal, send_goal_options);
91 current_goal_ = current_goal_future.get();
92 if (!current_goal_)
93 {
94 RCLCPP_ERROR(logger_, "Goal was rejected by server");
95 return false;
96 }
97 return true;
98}
99
100// TODO(JafarAbdi): Revise parameter lookup
101// void FollowJointTrajectoryControllerHandle::configure(XmlRpc::XmlRpcValue& config)
102//{
103// if (config.hasMember("path_tolerance"))
104// configure(config["path_tolerance"], "path_tolerance", goal_template_.path_tolerance);
105// if (config.hasMember("goal_tolerance"))
106// configure(config["goal_tolerance"], "goal_tolerance", goal_template_.goal_tolerance);
107// if (config.hasMember("goal_time_tolerance"))
108// goal_template_.goal_time_tolerance = ros::Duration(parseDouble(config["goal_time_tolerance"]));
109//}
110
111namespace
112{
113enum ToleranceVariables
114{
115 POSITION,
116 VELOCITY,
117 ACCELERATION
118};
119template <ToleranceVariables>
120double& variable(control_msgs::msg::JointTolerance& msg);
121
122template <>
123inline double& variable<POSITION>(control_msgs::msg::JointTolerance& msg)
124{
125 return msg.position;
126}
127template <>
128inline double& variable<VELOCITY>(control_msgs::msg::JointTolerance& msg)
129{
130 return msg.velocity;
131}
132template <>
133inline double& variable<ACCELERATION>(control_msgs::msg::JointTolerance& msg)
134{
135 return msg.acceleration;
136}
137
138const std::map<ToleranceVariables, std::string> VAR_NAME = { { POSITION, "position" },
139 { VELOCITY, "velocity" },
140 { ACCELERATION, "acceleration" } };
141const std::map<ToleranceVariables, decltype(&variable<POSITION>)> VAR_ACCESS = { { POSITION, &variable<POSITION> },
142 { VELOCITY, &variable<VELOCITY> },
143 { ACCELERATION,
144 &variable<ACCELERATION> } };
145
146const char* errorCodeToMessage(int error_code)
147{
148 switch (error_code)
149 {
150 case control_msgs::action::FollowJointTrajectory::Result::SUCCESSFUL:
151 return "SUCCESSFUL";
152 case control_msgs::action::FollowJointTrajectory::Result::INVALID_GOAL:
153 return "INVALID_GOAL";
154 case control_msgs::action::FollowJointTrajectory::Result::INVALID_JOINTS:
155 return "INVALID_JOINTS";
156 case control_msgs::action::FollowJointTrajectory::Result::OLD_HEADER_TIMESTAMP:
157 return "OLD_HEADER_TIMESTAMP";
158 case control_msgs::action::FollowJointTrajectory::Result::PATH_TOLERANCE_VIOLATED:
159 return "PATH_TOLERANCE_VIOLATED";
160 case control_msgs::action::FollowJointTrajectory::Result::GOAL_TOLERANCE_VIOLATED:
161 return "GOAL_TOLERANCE_VIOLATED";
162 default:
163 return "unknown error";
164 }
165}
166} // namespace
167
168// TODO(JafarAbdi): Revise parameter lookup
169// void FollowJointTrajectoryControllerHandle::configure(XmlRpc::XmlRpcValue& config, const std::string& config_name,
170// std::vector<control_msgs::JointTolerance>& tolerances)
171//{
172// if (isStruct(config)) // config should be either a struct of position, velocity, acceleration
173// {
174// for (ToleranceVariables var : { POSITION, VELOCITY, ACCELERATION })
175// {
176// if (!config.hasMember(VAR_NAME[var]))
177// continue;
178// XmlRpc::XmlRpcValue values = config[VAR_NAME[var]];
179// if (isArray(values, joints_.size()))
180// {
181// size_t i = 0;
182// for (const auto& joint_name : joints_)
183// VAR_ACCESS[var](getTolerance(tolerances, joint_name)) = parseDouble(values[i++]);
184// }
185// else
186// { // use common value for all joints
187// double value = parseDouble(values);
188// for (const auto& joint_name : joints_)
189// VAR_ACCESS[var](getTolerance(tolerances, joint_name)) = value;
190// }
191// }
192// }
193// else if (isArray(config)) // or an array of JointTolerance msgs
194// {
195// for (int i = 0; i < config.size(); ++i) // NOLINT(modernize-loop-convert)
196// {
197// control_msgs::JointTolerance& tol = getTolerance(tolerances, config[i]["name"]);
198// for (ToleranceVariables var : { POSITION, VELOCITY, ACCELERATION })
199// {
200// if (!config[i].hasMember(VAR_NAME[var]))
201// continue;
202// VAR_ACCESS[var](tol) = parseDouble(config[i][VAR_NAME[var]]);
203// }
204// }
205// }
206// else
207// ROS_WARN_STREAM_NAMED(LOGNAME, "Invalid " << config_name);
208//}
209
210control_msgs::msg::JointTolerance&
211FollowJointTrajectoryControllerHandle::getTolerance(std::vector<control_msgs::msg::JointTolerance>& tolerances,
212 const std::string& name)
213{
214 auto it = std::lower_bound(tolerances.begin(), tolerances.end(), name,
215 [](const control_msgs::msg::JointTolerance& lhs, const std::string& rhs) {
216 return lhs.name < rhs;
217 });
218 if (it == tolerances.cend() || it->name != name)
219 { // insert new entry if not yet available
220 it = tolerances.insert(it, control_msgs::msg::JointTolerance());
221 it->name = name;
222 }
223 return *it;
224}
225
227 const rclcpp_action::ClientGoalHandle<control_msgs::action::FollowJointTrajectory>::WrappedResult& wrapped_result)
228{
229 // Output custom error message for FollowJointTrajectoryResult if necessary
230 if (!wrapped_result.result)
231 {
232 RCLCPP_WARN_STREAM(logger_, "Controller '" << name_ << "' done, no result returned");
233 }
234 else if (wrapped_result.result->error_code == control_msgs::action::FollowJointTrajectory::Result::SUCCESSFUL)
235 {
236 RCLCPP_INFO_STREAM(logger_, "Controller '" << name_ << "' successfully finished");
237 }
238 else
239 {
240 RCLCPP_WARN_STREAM(logger_, "Controller '" << name_ << "' failed with error "
241 << errorCodeToMessage(wrapped_result.result->error_code) << ": "
242 << wrapped_result.result->error_string);
243 }
244 finishControllerExecution(wrapped_result.code);
245}
246
247} // end namespace moveit_simple_controller_manager
std::string getActionName() const
Get the full name of the action using the action namespace and base name.
void finishControllerExecution(const rclcpp_action::ResultCode &state)
Indicate that the controller handle is done executing the trajectory and set the controller manager h...
rclcpp_action::ClientGoalHandle< control_msgs::action::FollowJointTrajectory >::SharedPtr current_goal_
Current goal that has been sent to the action server.
bool isConnected() const
Check if the controller's action server is ready to receive action goals.
bool done_
Indicates whether the controller handle is done executing its current trajectory.
rclcpp_action::Client< control_msgs::action::FollowJointTrajectory >::SharedPtr controller_action_client_
Action client to send trajectories to the controller's action server.
void controllerDoneCallback(const rclcpp_action::ClientGoalHandle< control_msgs::action::FollowJointTrajectory >::WrappedResult &wrapped_result) override
static control_msgs::msg::JointTolerance & getTolerance(std::vector< control_msgs::msg::JointTolerance > &tolerances, const std::string &name)
bool sendTrajectory(const moveit_msgs::msg::RobotTrajectory &trajectory) override
Send a trajectory to the controller.