45 #include <rclcpp/rclcpp.hpp>
46 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
47 #include <tf2_ros/transform_listener.h>
52 int main(
int argc,
char* argv[])
54 rclcpp::init(argc, argv);
57 const rclcpp::Node::SharedPtr demo_node = std::make_shared<rclcpp::Node>(
"moveit_servo_demo");
61 const std::string param_namespace =
"moveit_servo";
62 const std::shared_ptr<const servo::ParamListener> servo_param_listener =
63 std::make_shared<const servo::ParamListener>(demo_node, param_namespace);
64 const servo::Params servo_params = servo_param_listener->get_params();
67 rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr trajectory_outgoing_cmd_pub =
68 demo_node->create_publisher<trajectory_msgs::msg::JointTrajectory>(servo_params.command_out_topic,
69 rclcpp::SystemDefaultsQoS());
78 std::this_thread::sleep_for(std::chrono::seconds(3));
83 robot_state->getJointModelGroup(servo_params.move_group_name);
90 TwistCommand target_twist{
"panda_link0", { 0.0, 0.0, 0.05, 0.0, 0.0, 0.4 } };
93 rclcpp::WallRate rate(1.0 / servo_params.publish_period);
95 std::chrono::seconds timeout_duration(4);
96 std::chrono::seconds time_elapsed(0);
97 const auto start_time = std::chrono::steady_clock::now();
100 std::deque<KinematicState> joint_cmd_rolling_window;
102 updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
110 const auto current_time = std::chrono::steady_clock::now();
111 time_elapsed = std::chrono::duration_cast<std::chrono::seconds>(current_time - start_time);
112 if (time_elapsed > timeout_duration)
114 RCLCPP_INFO_STREAM(demo_node->get_logger(),
"Timed out");
119 updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
122 trajectory_outgoing_cmd_pub->publish(msg.value());
124 if (!joint_cmd_rolling_window.empty())
126 robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
127 robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
133 RCLCPP_INFO(demo_node->get_logger(),
"Exiting demo.");
void setCommandType(const CommandType &command_type)
Set the type of incoming servo command.
KinematicState getCurrentRobotState(bool block_for_current_state) const
Get the current state of the robot as given by planning scene monitor. This may block if a current ro...
std::string getStatusMessage() const
Get the message associated with the current servo status.
StatusCode getStatus() const
Get the current status of servo.
KinematicState getNextJointState(const moveit::core::RobotStatePtr &robot_state, const ServoInput &command)
Computes the joint state required to follow the given command.
int main(int argc, char *argv[])
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...
planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const servo::Params &servo_params)
Creates the planning scene monitor used by servo.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.