43template <
class StartType, 
class GoalType>
 
   67  virtual std::
string getPlannerId() const = 0;
 
   75template <class StartType, class GoalType>
 
   81template <
class StartType, 
class GoalType>
 
   87template <
class StartType, 
class GoalType>
 
   93template <
class StartType, 
class GoalType>
 
   99template <
class StartType, 
class GoalType>
 
  105template <
class StartType, 
class GoalType>
 
 
  111template <
class StartType, 
class GoalType>
 
  115  req.planner_id = getPlannerId();
 
  119  req.max_acceleration_scaling_factor = 
acc_scale_;
 
  121  req.start_state = 
start_.toMoveitMsgsRobotState();
 
  122  req.goal_constraints.push_back(
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