![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
A Behavior to compute the inverse kinematics for a given set of target poses. More...
#include <compute_inverse_kinematics.hpp>
Public Member Functions | |
ComputeInverseKinematics (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
![]() | |
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(). | |
BT::NodeStatus | onRunning () override |
Required implementation of BT::StatefulActionNode::onRunning(). | |
void | onHalted () override |
Required implementation of BT::StatefulActionNode::onHalted(). | |
void | resetStatus () |
Resets the internal status of this node. | |
![]() | |
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. | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
static BT::KeyValueVector | metadata () |
Additional Inherited Members | |
![]() | |
virtual tl::expected< void, std::string > | doHalt () |
Optionally implement additional work needed to cleanly interrupt the async process. | |
void | notifyCanHalt () |
Called when runAsync() finishes to notify onHalted() that the async process has finished. | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
A Behavior to compute the inverse kinematics for a given set of target poses.
This behavior will compute the inverse kinematics for a given planning group and set of target poses. Each target pose needs to be associated with a tip link that needs to reach that pose. In the most common case (e.g. kinematic chains), target_poses
and tip_links
will contain a single element each. In more complex cases (e.g. kinematic trees, like a humanoid torso), target_poses
and tip_links
may contain multiple elements, therefore solving the IK problem simultaneously for multiple end-effectors.
Data Port Name | Port Type | Object Type |
---|---|---|
target_poses | Input | std::vector<geometry_msgs::msg::PoseStamped> |
tip_links | Input | std::vector<std::string> |
planning_scene_msg | Input | moveit_msgs::msg::PlanningScene |
planning_group_name | Input | std::string |
ik_timeout_s | Input | double |
link_padding | Input | double |
solution | Output | moveit_studio_agent_msgs::msg::RobotJointState |
moveit_studio::behaviors::ComputeInverseKinematics::ComputeInverseKinematics | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< BehaviorContext > & | shared_resources | ||
) |
|
static |
|
static |