50int main(
int argc,
char* argv[])
52 rclcpp::init(argc, argv);
55 const rclcpp::Node::SharedPtr demo_node = std::make_shared<rclcpp::Node>(
"moveit_servo_demo");
59 const std::string param_namespace =
"moveit_servo";
60 const std::shared_ptr<const servo::ParamListener> servo_param_listener =
61 std::make_shared<const servo::ParamListener>(demo_node, param_namespace);
62 const servo::Params servo_params = servo_param_listener->get_params();
65 rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr trajectory_outgoing_cmd_pub =
66 demo_node->create_publisher<trajectory_msgs::msg::JointTrajectory>(servo_params.command_out_topic,
67 rclcpp::SystemDefaultsQoS());
76 std::this_thread::sleep_for(std::chrono::seconds(3));
81 robot_state->getJointModelGroup(servo_params.move_group_name);
90 rclcpp::WallRate rate(1.0 / servo_params.publish_period);
92 std::chrono::seconds timeout_duration(3);
93 std::chrono::seconds time_elapsed(0);
94 const auto start_time = std::chrono::steady_clock::now();
97 std::deque<KinematicState> joint_cmd_rolling_window;
99 updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
107 const auto current_time = std::chrono::steady_clock::now();
108 time_elapsed = std::chrono::duration_cast<std::chrono::seconds>(current_time - start_time);
109 if (time_elapsed > timeout_duration)
111 RCLCPP_INFO_STREAM(demo_node->get_logger(),
"Timed out");
114 else if (status != StatusCode::INVALID)
116 updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
119 trajectory_outgoing_cmd_pub->publish(msg.value());
121 if (!joint_cmd_rolling_window.empty())
123 robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
124 robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
130 RCLCPP_INFO(demo_node->get_logger(),
"Exiting demo.");
std::optional< trajectory_msgs::msg::JointTrajectory > composeTrajectoryMessage(const servo::Params &servo_params, const std::deque< KinematicState > &joint_cmd_rolling_window)
Create a trajectory message from a rolling window queue of joint state commands. Method optionally re...
void updateSlidingWindow(KinematicState &next_joint_state, std::deque< KinematicState > &joint_cmd_rolling_window, double max_expected_latency, const rclcpp::Time &cur_time)
Adds a new joint state command to a queue containing commands over a time window. Also modifies the v...