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>
56 #include <default_request_adapter_parameters.hpp>
69 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
71 param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);
76 return std::string(
"CheckStartStateBounds");
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);
200 std::unique_ptr<default_request_adapter_parameters::ParamListener> param_listener_;
201 rclcpp::Logger logger_;
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 ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace.
std::string getDescription() const override
Get a description of this adapter.
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...
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...
rclcpp::Logger getLogger()
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)