moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
check_start_state_bounds.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan
36 * Desc: The CheckStartStateBounds adapter validates if the start state is within the joint limits
37 * specified in the URDF. The need for this adapter arises in situations where the joint limits for the physical robot
38 * are not properly configured. The robot may then end up in a configuration where one or more of its joints is slightly
39 * outside its joint limits. In this case, the motion planner is unable to plan since it will think that the starting
40 * state is outside joint limits. The “CheckStartStateBounds” planning request adapter can “fix” the start state by
41 * moving it to the joint limit. However, this is obviously not the right solution every time - e.g. where the joint is
42 * really outside its joint limits by a large amount. A parameter for the adapter specifies how much the joint can be
43 * outside its limits for it to be “fixable”.
44 */
45
49#include <class_loader/class_loader.hpp>
50#include <rclcpp/logger.hpp>
51#include <rclcpp/logging.hpp>
52#include <rclcpp/node.hpp>
53#include <rclcpp/parameter_value.hpp>
55
56#include <moveit_ros_planning/default_request_adapter_parameters.hpp>
57
59{
60
63{
64public:
65 CheckStartStateBounds() : logger_(moveit::getLogger("moveit.ros.check_start_state_bounds"))
66 {
67 }
68
69 void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
70 {
71 param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);
72 }
73
74 [[nodiscard]] std::string getDescription() const override
75 {
76 return std::string("CheckStartStateBounds");
77 }
78
79 [[nodiscard]] moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr& planning_scene,
80 planning_interface::MotionPlanRequest& req) const override
81 {
82 RCLCPP_DEBUG(logger_, "Running '%s'", getDescription().c_str());
83
84 // Get the specified start state
85 moveit::core::RobotState start_state = planning_scene->getCurrentState();
86 moveit::core::robotStateMsgToRobotState(planning_scene->getTransforms(), req.start_state, start_state);
87
88 // Get joint models
89 const std::vector<const moveit::core::JointModel*>& jmodels =
90 planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
91 planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
92 planning_scene->getRobotModel()->getJointModels();
93
94 // Read parameters
95 const auto params = param_listener_->get_params();
96
97 bool should_fix_state = false;
98 bool is_out_of_bounds = false;
99 for (const moveit::core::JointModel* jmodel : jmodels)
100 {
101 // Check if we have a revolute, continuous joint. If we do, then we only need to make sure
102 // it is within the model's declared bounds (usually -Pi, Pi), since the values wrap around.
103 // It is possible that the encoder maintains values outside the range [-Pi, Pi], to inform
104 // how many times the joint was wrapped. Because of this, we remember the offsets for continuous
105 // joints, and we undo them when the plan comes from the planner.
106 switch (jmodel->getType())
107 {
109 {
110 if (static_cast<const moveit::core::RevoluteJointModel*>(jmodel)->isContinuous())
111 {
112 double initial = start_state.getJointPositions(jmodel)[0];
113 start_state.enforceBounds(jmodel);
114 double after = start_state.getJointPositions(jmodel)[0];
115 if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
116 {
117 should_fix_state |= true;
118 }
119 }
120 break;
121 }
122 // Normalize yaw; no offset needs to be remembered
124 {
125 const double* p = start_state.getJointPositions(jmodel);
126 double copy[3] = { p[0], p[1], p[2] };
127 if (static_cast<const moveit::core::PlanarJointModel*>(jmodel)->normalizeRotation(copy))
128 {
129 start_state.setJointPositions(jmodel, copy);
130 should_fix_state |= true;
131 }
132 break;
133 }
135 {
136 // Normalize quaternions
137 const double* p = start_state.getJointPositions(jmodel);
138 double copy[7] = { p[0], p[1], p[2], p[3], p[4], p[5], p[6] };
139 if (static_cast<const moveit::core::FloatingJointModel*>(jmodel)->normalizeRotation(copy))
140 {
141 start_state.setJointPositions(jmodel, copy);
142 should_fix_state |= true;
143 }
144 break;
145 }
146 default:
147 {
148 break; // do nothing
149 }
150 }
151
152 // Check the joint against its bounds.
153 if (!start_state.satisfiesBounds(jmodel))
154 {
155 is_out_of_bounds |= true;
156
157 std::stringstream joint_values;
158 std::stringstream joint_bounds_low;
159 std::stringstream joint_bounds_hi;
160 const double* p = start_state.getJointPositions(jmodel);
161 for (std::size_t k = 0; k < jmodel->getVariableCount(); ++k)
162 {
163 joint_values << p[k] << ' ';
164 }
165 const moveit::core::JointModel::Bounds& b = jmodel->getVariableBounds();
166 for (const moveit::core::VariableBounds& variable_bounds : b)
167 {
168 joint_bounds_low << variable_bounds.min_position_ << ' ';
169 joint_bounds_hi << variable_bounds.max_position_ << ' ';
170 }
171 RCLCPP_ERROR(logger_,
172 "Joint '%s' from the starting state is outside bounds by: [%s] should be in "
173 "the range [%s], [%s].",
174 jmodel->getName().c_str(), joint_values.str().c_str(), joint_bounds_low.str().c_str(),
175 joint_bounds_hi.str().c_str());
176 }
177 }
178
179 // Package up the adapter result, changing the state if applicable.
180 auto status = moveit::core::MoveItErrorCode();
181 status.source = getDescription();
182 status.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
183
184 if (is_out_of_bounds || (!params.fix_start_state && should_fix_state))
185 {
186 status.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
187 status.message = std::string("Start state out of bounds.");
188 }
189 else if (params.fix_start_state && should_fix_state)
190 {
191 constexpr auto msg_string = "Normalized start state.";
192 status.message = msg_string;
193 RCLCPP_WARN(logger_, msg_string);
194 moveit::core::robotStateToRobotStateMsg(start_state, req.start_state);
195 }
196 return status;
197 }
198
199private:
200 std::unique_ptr<default_request_adapter_parameters::ParamListener> param_listener_;
201 rclcpp::Logger logger_;
202};
203} // namespace default_planning_request_adapters
204
The CheckStartStateBounds adapter validates if the start state is within the joint limits specified i...
moveit::core::MoveItErrorCode adapt(const planning_scene::PlanningSceneConstPtr &planning_scene, planning_interface::MotionPlanRequest &req) const override
Adapt the planning request.
void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
std::string getDescription() const override
Get a description of this adapter.
bool normalizeRotation(double *values) const
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
bool normalizeRotation(double *values) const
bool isContinuous() const
Check if this joint wraps around.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const double * getJointPositions(const std::string &joint_name) const
bool satisfiesBounds(double margin=0.0) const
void setJointPositions(const std::string &joint_name, const double *position)
Concept in MoveIt which can be used to modify the planning problem(pre-processing) in a planning pipe...
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
Main namespace for MoveIt.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
CLASS_LOADER_REGISTER_CLASS(default_planning_request_adapters::ResolveConstraintFrames, planning_interface::PlanningRequestAdapter)