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() :
95 const auto params = param_listener_->get_params();
97 bool should_fix_state =
false;
98 bool is_out_of_bounds =
false;
106 switch (jmodel->getType())
115 if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
117 should_fix_state |=
true;
126 double copy[3] = { p[0], p[1], p[2] };
130 should_fix_state |=
true;
138 double copy[7] = { p[0], p[1], p[2], p[3], p[4], p[5], p[6] };
142 should_fix_state |=
true;
155 is_out_of_bounds |=
true;
157 std::stringstream joint_values;
158 std::stringstream joint_bounds_low;
159 std::stringstream joint_bounds_hi;
161 for (std::size_t k = 0; k < jmodel->getVariableCount(); ++k)
163 joint_values << p[k] <<
' ';
168 joint_bounds_low << variable_bounds.min_position_ <<
' ';
169 joint_bounds_hi << variable_bounds.max_position_ <<
' ';
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());
182 status.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
184 if (is_out_of_bounds || (!params.fix_start_state && should_fix_state))
186 status.val = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
187 status.message = std::string(
"Start state out of bounds.");
189 else if (params.fix_start_state && should_fix_state)
191 constexpr auto msg_string =
"Normalized start state.";
192 status.message = msg_string;
193 RCLCPP_WARN(logger_, msg_string);