27 template <
class StartType,
class GoalType>
59 template <
class StartType,
class GoalType>
65 template <
class StartType,
class GoalType>
71 template <
class StartType,
class GoalType>
77 template <
class StartType,
class GoalType>
83 template <
class StartType,
class GoalType>
89 template <
class StartType,
class GoalType>
95 template <
class StartType,
class GoalType>
102 req.max_velocity_scaling_factor = this->
vel_scale_;
103 req.max_acceleration_scaling_factor = this->
acc_scale_;
105 req.start_state = this->
start_.toMoveitMsgsRobotState();
106 req.goal_constraints.push_back(this->
goal_.toGoalConstraints());
StartType & getStartConfiguration()
Base class for commands storing all general information of a command.
void setGoalConfiguration(GoalType goal)
virtual std::string getPlannerId() const =0
void setStartConfiguration(StartType start)
std::string planning_group_
GoalType & getGoalConfiguration()
moveit_msgs::MotionPlanRequest MotionPlanRequest
virtual planning_interface::MotionPlanRequest toRequest() const override
virtual ~BaseCmd()=default