Go to the documentation of this file.
42 #include <boost/optional.hpp>
92 const double target_pose_timeout);
98 void updatePIDConfig(
const double x_proportional_gain,
const double x_integral_gain,
const double x_derivative_gain,
99 const double y_proportional_gain,
const double y_integral_gain,
const double y_derivative_gain,
100 const double z_proportional_gain,
const double z_integral_gain,
const double z_derivative_gain,
101 const double angular_proportional_gain,
const double angular_integral_gain,
102 const double angular_derivative_gain);
104 void getPIDErrors(
double& x_error,
double& y_error,
double& z_error,
double& orientation_error);
119 std::unique_ptr<moveit_servo::Servo>
servo_;
bool haveRecentTargetPose(const double timeout)
Return true if a target pose has been received within timeout [seconds].
@ NO_RECENT_END_EFFECTOR_POSE
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
bool haveRecentEndEffectorPose(const double timeout)
Return true if an end effector pose has been received within timeout [seconds].
void getPIDErrors(double &x_error, double &y_error, double &z_error, double &orientation_error)
void resetTargetPose()
Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.
std::vector< control_toolbox::Pid > cartesian_orientation_pids_
std::vector< control_toolbox::Pid > cartesian_position_pids_
std::string move_group_name_
geometry_msgs::PoseStamped target_pose_
void updateControllerSetpoints()
Update PID controller target positions & orientations.
ros::Time command_frame_transform_stamp_
void doPostMotionReset()
Reset flags and PID controllers after a motion completes.
void updateControllerStateMeasurements()
Update PID controller states (positions & orientations)
bool satisfiesPoseTolerance(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance)
Check if XYZ, roll/pitch/yaw tolerances are satisfied.
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 udpate.
tf2_ros::TransformListener transform_listener_
robot_model::RobotModelConstPtr robot_model_
geometry_msgs::TwistStampedConstPtr calculateTwistCommand()
Use PID controllers to calculate a full spatial velocity toward a pose.
std::shared_ptr< PoseTracking > PoseTrackingPtr
Eigen::Isometry3d command_frame_transform_
void stopMotion()
A method for a different thread to stop motion and return early from control loop.
boost::optional< double > angular_error_
ros::Publisher twist_stamped_pub_
std::mutex target_pose_mtx_
std::atomic< bool > stop_requested_
PIDConfig angular_pid_config_
const moveit::core::JointModelGroup * joint_model_group_
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
ros::Subscriber target_pose_sub_
tf2_ros::Buffer transform_buffer_
PoseTracking(const ros::NodeHandle &nh, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor)
Constructor. Loads ROS parameters under the given namespace.
const std::unordered_map< PoseTrackingStatusCode, std::string > POSE_TRACKING_STATUS_CODE_MAP({ { PoseTrackingStatusCode::INVALID, "Invalid" }, { PoseTrackingStatusCode::SUCCESS, "Success" }, { PoseTrackingStatusCode::NO_RECENT_TARGET_POSE, "No recent target pose" }, { PoseTrackingStatusCode::NO_RECENT_END_EFFECTOR_POSE, "No recent end effector pose" }, { PoseTrackingStatusCode::STOP_REQUESTED, "Stop requested" } })
void readROSParams()
Load ROS parameters for controller settings.
void targetPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
Subscribe to the target pose on this topic.
std::unique_ptr< moveit_servo::Servo > servo_
std::string planning_frame_
void initializePID(const PIDConfig &pid_config, std::vector< control_toolbox::Pid > &pid_vector)
Initialize a PID controller and add it to vector of controllers.
bool getCommandFrameTransform(geometry_msgs::TransformStamped &transform)
moveit_servo
Author(s): Brian O'Neil, Andy Zelenak
, Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56