66int main(
int argc,
char* argv[])
68 rclcpp::init(argc, argv);
71 const rclcpp::Node::SharedPtr demo_node = std::make_shared<rclcpp::Node>(
"moveit_servo_demo");
75 const std::string param_namespace =
"moveit_servo";
76 const std::shared_ptr<const servo::ParamListener> servo_param_listener =
77 std::make_shared<const servo::ParamListener>(demo_node, param_namespace);
78 const servo::Params servo_params = servo_param_listener->get_params();
81 rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr trajectory_outgoing_cmd_pub =
82 demo_node->create_publisher<trajectory_msgs::msg::JointTrajectory>(servo_params.command_out_topic,
83 rclcpp::SystemDefaultsQoS());
91 const auto get_current_pose = [](
const std::string& target_frame,
const moveit::core::RobotStatePtr& robot_state) {
92 return robot_state->getGlobalLinkTransform(target_frame);
97 std::this_thread::sleep_for(std::chrono::seconds(3));
102 robot_state->getJointModelGroup(servo_params.move_group_name);
109 target_pose.
frame_id = K_BASE_FRAME;
112 target_pose.
pose = get_current_pose(K_TIP_FRAME, robot_state);
115 Eigen::Isometry3d terminal_pose = target_pose.
pose;
116 terminal_pose.rotate(Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitZ()));
117 terminal_pose.translate(Eigen::Vector3d(0.0, 0.0, -0.1));
120 Eigen::Vector3d linear_step_size{ 0.0, 0.0, -0.001 };
121 Eigen::AngleAxisd angular_step_size(0.01, Eigen::Vector3d::UnitZ());
125 rclcpp::WallRate servo_rate(1 / servo_params.publish_period);
128 std::deque<KinematicState> joint_cmd_rolling_window;
130 updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
132 bool satisfies_linear_tolerance =
false;
133 bool satisfies_angular_tolerance =
false;
134 bool stop_tracking =
false;
135 while (!stop_tracking && rclcpp::ok())
138 target_pose.
pose = get_current_pose(K_TIP_FRAME, robot_state);
139 satisfies_linear_tolerance |= target_pose.
pose.translation().isApprox(terminal_pose.translation(),
140 servo_params.pose_tracking.linear_tolerance);
141 satisfies_angular_tolerance |=
142 target_pose.
pose.rotation().isApprox(terminal_pose.rotation(), servo_params.pose_tracking.angular_tolerance);
143 stop_tracking = satisfies_linear_tolerance && satisfies_angular_tolerance;
146 if (!satisfies_linear_tolerance)
148 target_pose.
pose.translate(linear_step_size);
150 if (!satisfies_angular_tolerance)
152 target_pose.
pose.rotate(angular_step_size);
158 if (status != StatusCode::INVALID)
160 updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
163 trajectory_outgoing_cmd_pub->publish(msg.value());
165 if (!joint_cmd_rolling_window.empty())
167 robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
168 robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
175 RCLCPP_INFO_STREAM(demo_node->get_logger(),
"REACHED : " << stop_tracking);
176 RCLCPP_INFO(demo_node->get_logger(),
"Exiting demo.");