42 #include <control_toolbox/pid.hpp>
47 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
48 #include <tf2_ros/transform_listener.h>
49 #include <rclcpp/rclcpp.hpp>
94 const double target_pose_timeout);
100 void updatePIDConfig(
const double x_proportional_gain,
const double x_integral_gain,
const double x_derivative_gain,
101 const double y_proportional_gain,
const double y_integral_gain,
const double y_derivative_gain,
102 const double z_proportional_gain,
const double z_integral_gain,
const double z_derivative_gain,
103 const double angular_proportional_gain,
const double angular_integral_gain,
104 const double angular_derivative_gain);
106 void getPIDErrors(
double& x_error,
double& y_error,
double& z_error,
double& orientation_error);
121 std::unique_ptr<moveit_servo::Servo>
servo_;
125 void readROSParams();
128 void initializePID(
const PIDConfig& pid_config, std::vector<control_toolbox::Pid>& pid_vector);
131 bool haveRecentTargetPose(
const double timeout);
134 bool haveRecentEndEffectorPose(
const double timeout);
137 bool satisfiesPoseTolerance(
const Eigen::Vector3d& positional_tolerance,
const double angular_tolerance);
140 void targetPoseCallback(
const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg);
143 void updateControllerSetpoints();
146 void updateControllerStateMeasurements();
149 geometry_msgs::msg::TwistStamped::ConstSharedPtr calculateTwistCommand();
152 void doPostMotionReset();
154 rclcpp::Node::SharedPtr node_;
157 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
158 moveit::core::RobotModelConstPtr robot_model_;
160 std::string move_group_name_;
162 rclcpp::WallRate loop_rate_;
165 rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr twist_stamped_pub_;
167 std::vector<control_toolbox::Pid> cartesian_position_pids_;
168 std::vector<control_toolbox::Pid> cartesian_orientation_pids_;
170 PIDConfig x_pid_config_, y_pid_config_, z_pid_config_, angular_pid_config_;
173 Eigen::Isometry3d command_frame_transform_;
174 rclcpp::Time command_frame_transform_stamp_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
175 geometry_msgs::msg::PoseStamped target_pose_;
176 mutable std::mutex target_pose_mtx_;
179 rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr target_pose_sub_;
181 tf2_ros::Buffer transform_buffer_;
182 tf2_ros::TransformListener transform_listener_;
185 std::string planning_frame_;
188 std::atomic<bool> stop_requested_;
190 std::optional<double> angular_error_;
void getPIDErrors(double &x_error, double &y_error, double &z_error, double &orientation_error)
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
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.
std::unique_ptr< moveit_servo::Servo > servo_
bool getCommandFrameTransform(geometry_msgs::msg::TransformStamped &transform)
void stopMotion()
A method for a different thread to stop motion and return early from control loop.
void resetTargetPose()
Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.
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.
Vec3fX< details::Vec3Data< double > > Vector3d
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" } })
std::shared_ptr< PoseTracking > PoseTrackingPtr
@ NO_RECENT_END_EFFECTOR_POSE
std::shared_ptr< const ServoParameters > SharedConstPtr