MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
|
Generate a joint-space point-to-point trajectory to move the robot from the start joint state to the target joint state. More...
#include <generate_point_to_point_trajectory.hpp>
Public Member Functions | |
GeneratePointToPointTrajectory (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
Constructor for GeneratePointToPointTrajectory behavior. More... | |
BT::NodeStatus | tick () override |
Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
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... | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
Generate a joint-space point-to-point trajectory to move the robot from the start joint state to the target joint state.
The output (joint_trajectory_msg
) is a timed joint-space trajectory that is ready to be sent to a trajectory tracking controller. The first point in the trajectory will have a time_from_start
equal to the value specified on the start_time
input port and will be sampled at the rate specified on the trajectory_sampling_rate
input port. 'velocity_scale_factor', 'acceleration_scale_factor', and 'jerk_scale_factor' control the desired joint-space motion as a fraction ([0,1]) of the maximum joint velocities, accelerations, and jerks defined in the MoveIt configs.
The behavior returns SUCCESS if a trajectory was successfully computed between the start and target joint states, or FAILURE otherwise.
Data Port Name | Port Type | Object Type |
---|---|---|
planning_group_name | Input | std::string |
start_state | Input | moveit_studio_agent_msgs::msg::RobotJointState |
target_state | Input | moveit_studio_agent_msgs::msg::RobotJointState |
velocity_scale_factor | Input | double |
acceleration_scale_factor | Input | double |
jerk_scale_factor | Input | double |
trajectory_sampling_rate | Input | unsigned int |
start_time | Input | double |
joint_trajectory_msg | Output | trajectory_msgs::msg::JointTrajectory |
moveit_studio::behaviors::GeneratePointToPointTrajectory::GeneratePointToPointTrajectory | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
Constructor for GeneratePointToPointTrajectory behavior.
|
static |
|
static |
|
override |