MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::ComputeLinkPoseForwardKinematics Class Reference

This Behavior computes the Cartesian Pose of a link from a given Joint State. If the Joint State message does not contain all of the joints for calculating the pose, it will use the existing joint states for the missing joint states. More...

#include <compute_link_pose_forward_kinematics.hpp>

Inheritance diagram for moveit_studio::behaviors::ComputeLinkPoseForwardKinematics:
Collaboration diagram for moveit_studio::behaviors::ComputeLinkPoseForwardKinematics:

Classes

struct  InfoAndWarnings
 

Public Member Functions

 ComputeLinkPoseForwardKinematics (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources)
 
BT::NodeStatus tick () override
 
tl::expected< geometry_msgs::msg::PoseStamped, std::string > compute_link_pose_forward_kinematics (const moveit_msgs::msg::PlanningScene &planning_scene, const std::shared_ptr< moveit::core::RobotModel > &robot_model, const sensor_msgs::msg::JointState &joint_state_for_fk, const std::string &link_name, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, InfoAndWarnings &info_and_warnings) const
 
- 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.
 

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< BehaviorContextshared_resources_
 

Detailed Description

This Behavior computes the Cartesian Pose of a link from a given Joint State. If the Joint State message does not contain all of the joints for calculating the pose, it will use the existing joint states for the missing joint states.

Data Port Name Port Type Object Type
planning_scene input moveit_msgs::msg::PlanningScene
joint_state input sensor_msgs::msg::JointState
link_name input std::string
link_pose output geometry_msgs::msg::PoseStamped

Constructor & Destructor Documentation

◆ ComputeLinkPoseForwardKinematics()

moveit_studio::behaviors::ComputeLinkPoseForwardKinematics::ComputeLinkPoseForwardKinematics ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources 
)

Member Function Documentation

◆ compute_link_pose_forward_kinematics()

tl::expected< geometry_msgs::msg::PoseStamped, std::string > moveit_studio::behaviors::ComputeLinkPoseForwardKinematics::compute_link_pose_forward_kinematics ( const moveit_msgs::msg::PlanningScene &  planning_scene,
const std::shared_ptr< moveit::core::RobotModel > &  robot_model,
const sensor_msgs::msg::JointState &  joint_state_for_fk,
const std::string &  link_name,
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources,
InfoAndWarnings info_and_warnings 
) const

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::ComputeLinkPoseForwardKinematics::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::ComputeLinkPoseForwardKinematics::providedPorts ( )
static

◆ tick()

BT::NodeStatus moveit_studio::behaviors::ComputeLinkPoseForwardKinematics::tick ( )
override

The documentation for this class was generated from the following files: