Given a Cartesian-space path, plan a joint-space trajectory to move the robot tip along the path.
More...
|
| PlanCartesianPath (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for PlanCartesianPath behavior. More...
|
|
| PlanCartesianPath (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPlanningScene >> client_interface) |
| Constructor for PlanCartesianPath behavior that allows for mocking of the rclcpp service client. More...
|
|
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructs ServiceClientBehaviorBase using the RclcppClientInterface. More...
|
|
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPlanningScene >> client_interface) |
| Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase. More...
|
|
virtual | ~ServiceClientBehaviorBase ()=default |
|
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
virtual | ~AsyncBehaviorBase ()=default |
|
BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart(). More...
|
|
BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning(). More...
|
|
void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted(). More...
|
|
void | resetStatus () |
| Resets the internal status of this node. More...
|
|
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node. More...
|
|
Given a Cartesian-space path, plan a joint-space trajectory to move the robot tip along the path.
The kinematics are solved for the given 'tip_link' of the given planning group ('planning_group_name'). The path to follow is given by 'path', which can contain waypoints in different frames. All of them will be transformed to a common frame internally. An additional tip offset can be specified via the 'tip_offset' input port (x,y,z, r,p,y, i.e. needs to be size 6). The tip offset is applied to the 'tip_link' frame before generating the reference path, so for example, if 'tip_offset' is set to {0, 0, -0.1, 0, 0, 0}, the tip_link frame origin will be translated 0.1 meters in the negative z direction, and the reference path will be generated using that translated frame. I.e. at the end of the path, the end-effector will be 0.1 meter closer to an object following the -0.1 z axis translation. If 'position_only' is set to true, the solver will only solve for the translational part of the path, i.e. orientation will be unconstained. Use 'blending_radius' to control the amount of rounding at the path corners. 'velocity_scale_factor' and 'acceleration_scale_factor' control the desired joint-space velocity as a fraction ([0,1]) of the maximum joint velocities and accelerations defined in the MoveIt configs. Finally, the rate of the output trajectory can be configured with 'trajectory_sampling_rate', as samples per seconds.
The output (joint_trajectory_msg
) is a timed joint-space trajectory that is ready to be sent to a trajectory tracking controller.
The behavior returns SUCCESS if IK was successfully computed for the entire path, or FAILURE otherwise. In any case, the debug_solution
output port will include the feasible part of the trajectory, for visualization and debugging.
Data Port Name | Port Type | Object Type |
path | Input | std::vector<geometry_msgs::msg::PoseStamped> |
planning_group_name | Input | std::string |
tip_link | Input | std::string |
tip_offset | Input | std::vector<double> |
position_only | Input | bool |
blending_radius | Input | double |
ik_cartesian_space_density | Input | double |
ik_joint_space_density | Input | double |
velocity_scale_factor | Input | double |
acceleration_scale_factor | Input | double |
trajectory_sampling_rate | Input | int |
joint_trajectory_msg | Output | trajectory_msgs::msg::JointTrajectory |
debug_solution | Output | moveit_task_constructor_msgs::msg::Solution |