Class CpMotionPlanner
Defined in File cp_motion_planner.hpp
Inheritance Relationships
Base Type
public smacc2::ISmaccComponent
Class Documentation
-
class CpMotionPlanner : public smacc2::ISmaccComponent
Component for centralized motion planning operations.
This component wraps all MoveGroupInterface planning operations to provide a consistent interface for planning motions. It supports planning to:
Cartesian poses
Joint configurations
Named targets
Cartesian paths
Pattern: API wrapper component with result types
Public Functions
-
CpMotionPlanner() = default
-
virtual ~CpMotionPlanner() = default
-
inline void onInitialize() override
Initialize the component and get reference to ClMoveit2z client.
-
inline PlanningResult planToPose(const geometry_msgs::msg::PoseStamped &target, const std::optional<std::string> &tipLink = std::nullopt, const PlanningOptions &options = {})
Plan to a Cartesian pose.
- Parameters:
target – Target pose (position and orientation)
tipLink – End effector tip link (optional, uses default if not specified)
options – Planning configuration options
- Returns:
PlanningResult with success status and computed plan
-
inline PlanningResult planToJointTarget(const std::map<std::string, double> &jointTargets, const PlanningOptions &options = {})
Plan to joint values.
- Parameters:
jointTargets – Map of joint names to target values
options – Planning configuration options
- Returns:
PlanningResult with success status and computed plan
-
inline PlanningResult planCartesianPath(const std::vector<geometry_msgs::msg::Pose> &waypoints, double maxStep = 0.01, double jumpThreshold = 0.0, bool avoidCollisions = true)
Plan a Cartesian path.
- Parameters:
waypoints – Vector of waypoint poses
maxStep – Maximum distance between path points (meters)
jumpThreshold – Maximum joint jump threshold (0.0 = disabled)
avoidCollisions – Whether to check for collisions
- Returns:
PlanningResult with success status and computed trajectory
-
inline moveit::core::RobotStatePtr getCurrentState(double waitTime = 1.0)
Get current robot state.
- Parameters:
waitTime – Maximum time to wait for state (seconds)
- Returns:
Pointer to current robot state, or nullptr if unavailable