43 template <
class StartType,
class GoalType>
67 virtual std::
string getPlannerId() const = 0;
75 template <class StartType, class GoalType>
81 template <
class StartType,
class GoalType>
87 template <
class StartType,
class GoalType>
93 template <
class StartType,
class GoalType>
99 template <
class StartType,
class GoalType>
105 template <
class StartType,
class GoalType>
111 template <
class StartType,
class GoalType>
115 req.planner_id = getPlannerId();
118 req.max_velocity_scaling_factor = this->
vel_scale_;
119 req.max_acceleration_scaling_factor = this->
acc_scale_;
121 req.start_state = this->
start_.toMoveitMsgsRobotState();
122 req.goal_constraints.push_back(this->
goal_.toGoalConstraints());
void setStartConfiguration(StartType start)
void setGoalConfiguration(GoalType goal)
StartType & getStartConfiguration()
BaseCmd(const BaseCmd &)=default
planning_interface::MotionPlanRequest toRequest() const override
BaseCmd(BaseCmd &&) noexcept=default
GoalType & getGoalConfiguration()
Base class for commands storing all general information of a command.
std::string planning_group_
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest