moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | List of all members
moveit_servo::PoseTracking Class Reference

#include <pose_tracking.h>

Public Member Functions

 PoseTracking (const rclcpp::Node::SharedPtr &node, const ServoParameters::SharedConstPtr &servo_parameters, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
 Constructor. Loads ROS parameters under the given namespace. More...
 
PoseTrackingStatusCode moveToPose (const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
 
void stopMotion ()
 A method for a different thread to stop motion and return early from control loop. More...
 
void updatePIDConfig (const double x_proportional_gain, const double x_integral_gain, const double x_derivative_gain, const double y_proportional_gain, const double y_integral_gain, const double y_derivative_gain, const double z_proportional_gain, const double z_integral_gain, const double z_derivative_gain, const double angular_proportional_gain, const double angular_integral_gain, const double angular_derivative_gain)
 Change PID parameters. Motion is stopped before the update. More...
 
void getPIDErrors (double &x_error, double &y_error, double &z_error, double &orientation_error)
 
bool getCommandFrameTransform (geometry_msgs::msg::TransformStamped &transform)
 
void resetTargetPose ()
 Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints. More...
 

Public Attributes

std::unique_ptr< moveit_servo::Servoservo_
 

Detailed Description

Class PoseTracking - subscribe to a target pose. Servo toward the target pose.

Definition at line 86 of file pose_tracking.h.

Constructor & Destructor Documentation

◆ PoseTracking()

moveit_servo::PoseTracking::PoseTracking ( const rclcpp::Node::SharedPtr &  node,
const ServoParameters::SharedConstPtr servo_parameters,
const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor 
)

Constructor. Loads ROS parameters under the given namespace.

Definition at line 75 of file pose_tracking.cpp.

Member Function Documentation

◆ getCommandFrameTransform()

bool moveit_servo::PoseTracking::getCommandFrameTransform ( geometry_msgs::msg::TransformStamped &  transform)

Get the End Effector link transform. The transform from the MoveIt planning frame to EE link

Parameters
transformthe transform that will be calculated
Returns
true if a valid transform was available

Definition at line 405 of file pose_tracking.cpp.

◆ getPIDErrors()

void moveit_servo::PoseTracking::getPIDErrors ( double &  x_error,
double &  y_error,
double &  z_error,
double &  orientation_error 
)

Definition at line 389 of file pose_tracking.cpp.

◆ moveToPose()

PoseTrackingStatusCode moveit_servo::PoseTracking::moveToPose ( const Eigen::Vector3d &  positional_tolerance,
const double  angular_tolerance,
const double  target_pose_timeout 
)

Definition at line 109 of file pose_tracking.cpp.

◆ resetTargetPose()

void moveit_servo::PoseTracking::resetTargetPose ( )

Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.

Definition at line 398 of file pose_tracking.cpp.

◆ stopMotion()

void moveit_servo::PoseTracking::stopMotion ( )

A method for a different thread to stop motion and return early from control loop.

Definition at line 329 of file pose_tracking.cpp.

Here is the caller graph for this function:

◆ updatePIDConfig()

void moveit_servo::PoseTracking::updatePIDConfig ( const double  x_proportional_gain,
const double  x_integral_gain,
const double  x_derivative_gain,
const double  y_proportional_gain,
const double  y_integral_gain,
const double  y_derivative_gain,
const double  z_proportional_gain,
const double  z_integral_gain,
const double  z_derivative_gain,
const double  angular_proportional_gain,
const double  angular_integral_gain,
const double  angular_derivative_gain 
)

Change PID parameters. Motion is stopped before the update.

Definition at line 356 of file pose_tracking.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ servo_

std::unique_ptr<moveit_servo::Servo> moveit_servo::PoseTracking::servo_

Definition at line 121 of file pose_tracking.h.


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