39 #include <std_msgs/msg/int8.hpp> 
   40 #include <geometry_msgs/msg/transform_stamped.hpp> 
   50 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"moveit_servo.pose_tracking_demo");
 
   56   StatusMonitor(
const rclcpp::Node::SharedPtr& node, 
const std::string& topic)
 
   58     sub_ = node->create_subscription<std_msgs::msg::Int8>(topic, rclcpp::SystemDefaultsQoS(),
 
   59                                                           [
this](
const std_msgs::msg::Int8::ConstSharedPtr& msg) {
 
   65   void statusCB(
const std_msgs::msg::Int8::ConstSharedPtr& msg)
 
   68     if (latest_status != status_)
 
   70       status_ = latest_status;
 
   72       RCLCPP_INFO_STREAM(LOGGER, 
"Servo status: " << status_str);
 
   77   rclcpp::Subscription<std_msgs::msg::Int8>::SharedPtr sub_;
 
   85 int main(
int argc, 
char** argv)
 
   87   rclcpp::init(argc, argv);
 
   88   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"pose_tracking_demo");
 
   90   rclcpp::executors::SingleThreadedExecutor executor;
 
   91   executor.add_node(node);
 
   92   std::thread executor_thread([&executor]() { executor.spin(); });
 
   96   if (servo_parameters == 
nullptr)
 
   98     RCLCPP_FATAL(LOGGER, 
"Could not get servo parameters!");
 
  104   planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(node, 
"robot_description");
 
  107     RCLCPP_ERROR_STREAM(LOGGER, 
"Error in setting up the PlanningSceneMonitor.");
 
  123     RCLCPP_ERROR_STREAM(LOGGER, 
"Error waiting for current robot state in PlanningSceneMonitor.");
 
  131   auto target_pose_pub =
 
  132       node->create_publisher<geometry_msgs::msg::PoseStamped>(
"target_pose", rclcpp::SystemDefaultsQoS());
 
  135   StatusMonitor status_monitor(node, servo_parameters->status_topic);
 
  138   double rot_tol = 0.01;
 
  141   geometry_msgs::msg::TransformStamped current_ee_tf;
 
  145   geometry_msgs::msg::PoseStamped target_pose;
 
  146   target_pose.header.frame_id = current_ee_tf.header.frame_id;
 
  147   target_pose.pose.position.x = current_ee_tf.transform.translation.x;
 
  148   target_pose.pose.position.y = current_ee_tf.transform.translation.y;
 
  149   target_pose.pose.position.z = current_ee_tf.transform.translation.z;
 
  150   target_pose.pose.orientation = current_ee_tf.transform.rotation;
 
  153   target_pose.pose.position.x += 0.1;
 
  160   target_pose.header.stamp = node->now();
 
  161   target_pose_pub->publish(target_pose);
 
  164   std::thread move_to_pose_thread([&tracker, &lin_tol, &rot_tol] {
 
  167     RCLCPP_INFO_STREAM(LOGGER, 
"Pose tracker exited with status: " 
  171   rclcpp::WallRate loop_rate(50);
 
  172   for (
size_t i = 0; i < 500; ++i)
 
  176     target_pose.pose.position.z += 0.0004;
 
  177     target_pose.header.stamp = node->now();
 
  178     target_pose_pub->publish(target_pose);
 
  184   move_to_pose_thread.join();
 
  188   executor_thread.join();
 
StatusMonitor(const rclcpp::Node::SharedPtr &node, const std::string &topic)
 
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
 
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.
 
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
The name of the topic used by default for receiving collision objects in the world.
 
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
 
@ UPDATE_SCENE
The entire scene was updated.
 
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" } })
 
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_APPROACHING_SINGULARITY, "Moving closer to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" }, { StatusCode::DECELERATE_FOR_LEAVING_SINGULARITY, "Moving away from a singularity, decelerating" } })
 
const rclcpp::Logger LOGGER
 
int main(int argc, char **argv)
 
static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)