38 #include <boost/math/constants/constants.hpp>
41 #include <class_loader/class_loader.hpp>
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
45 #include <rclcpp/parameter_value.hpp>
49 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.fix_start_state_bounds");
57 void initialize(
const rclcpp::Node::SharedPtr& node,
const std::string& parameter_namespace)
override
66 return "Fix Start State Bounds";
71 std::vector<std::size_t>& added_path_index)
const override
79 const std::vector<const moveit::core::JointModel*>& jmodels =
80 planning_scene->getRobotModel()->hasJointModelGroup(req.group_name) ?
81 planning_scene->getRobotModel()->getJointModelGroup(req.group_name)->getJointModels() :
84 bool change_req =
false;
100 if (fabs(initial - after) > std::numeric_limits<double>::epsilon())
109 double copy[3] = {
p[0],
p[1],
p[2] };
121 double copy[7] = {
p[0],
p[1],
p[2],
p[3],
p[4],
p[5],
p[6] };
131 moveit::core::RobotStatePtr prefix_state;
139 prefix_state = std::make_shared<moveit::core::RobotState>(start_state);
142 RCLCPP_INFO(LOGGER,
"Starting state is just outside bounds (joint '%s'). Assuming within bounds.",
143 jmodel->getName().c_str());
147 std::stringstream joint_values;
148 std::stringstream joint_bounds_low;
149 std::stringstream joint_bounds_hi;
151 for (std::size_t k = 0; k < jmodel->getVariableCount(); ++k)
152 joint_values <<
p[k] <<
" ";
156 joint_bounds_low << variable_bounds.min_position_ <<
" ";
157 joint_bounds_hi << variable_bounds.max_position_ <<
" ";
160 "Joint '%s' from the starting state is outside bounds by a significant margin: [%s] should be in "
161 "the range [%s], [%s] but the error above the ~%s parameter (currently set to %f)",
162 jmodel->getName().c_str(), joint_values.str().c_str(), joint_bounds_low.str().c_str(),
184 res.
trajectory_->setWayPointDurationFromPrevious(0, std::min(max_dt_offset_,
186 res.
trajectory_->addPrefixWayPoint(prefix_state, 0.0);
188 for (std::size_t& added_index : added_path_index)
190 added_path_index.push_back(0);
197 rclcpp::Node::SharedPtr node_;
199 double max_dt_offset_;
std::string getDescription() const override
Get a short string that identifies the planning request adapter.
static const std::string BOUNDS_PARAM_NAME
void initialize(const rclcpp::Node::SharedPtr &node, const std::string ¶meter_namespace) override
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const override
Adapt the planning request if needed, call the planner function planner and update the planning respo...
static const std::string DT_PARAM_NAME
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.
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)
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string ¶meter_namespace, const std::string ¶meter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
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.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
robot_trajectory::RobotTrajectoryPtr trajectory_
CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager)