91 const std::vector<const moveit::core::JointModel*>& jmodels =
92 planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
93 planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
97 const auto params = param_listener_->get_params();
99 bool should_fix_state =
false;
100 bool is_out_of_bounds =
false;
108 switch (jmodel->getType())
117 if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
119 should_fix_state |=
true;
128 double copy[3] = { p[0], p[1], p[2] };
132 should_fix_state |=
true;
140 double copy[7] = { p[0], p[1], p[2], p[3], p[4], p[5], p[6] };
144 should_fix_state |=
true;
157 is_out_of_bounds |=
true;
159 std::stringstream joint_values;
160 std::stringstream joint_bounds_low;
161 std::stringstream joint_bounds_hi;
163 for (std::size_t k = 0; k < jmodel->getVariableCount(); ++k)
165 joint_values << p[k] <<
' ';
170 joint_bounds_low << variable_bounds.min_position_ <<
' ';
171 joint_bounds_hi << variable_bounds.max_position_ <<
' ';
173 RCLCPP_ERROR(logger_,
174 "Joint '%s' from the starting state is outside bounds by: [%s] should be in "
175 "the range [%s], [%s].",
176 jmodel->getName().c_str(), joint_values.str().c_str(), joint_bounds_low.str().c_str(),
177 joint_bounds_hi.str().c_str());
184 status.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
186 if (is_out_of_bounds || (!params.fix_start_state && should_fix_state))
188 status.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
189 status.message = std::string(
"Start state out of bounds.");
191 else if (params.fix_start_state && should_fix_state)
193 constexpr auto msg_string =
"Normalized start state.";
194 status.message = msg_string;
195 RCLCPP_WARN(logger_, msg_string);