moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
demo_joint_jog.cpp
Go to the documentation of this file.
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2023, PickNik Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions are met:
9 *
10 * * Redistributions of source code must retain the above copyright notice, this
11 * list of conditions and the following disclaimer.
12 *
13 * * Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * and/or other materials provided with the distribution.
16 *
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived from
19 * this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24 * ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 *******************************************************************************/
33
34/* Title : demo_joint_jog.cpp
35 * Project : moveit_servo
36 * Created : 05/27/2023
37 * Author : V Mohammed Ibrahim
38 *
39 * Description : Example of controlling a robot through joint jog commands via the C++ API.
40 */
41
42#include <chrono>
45#include <rclcpp/rclcpp.hpp>
47
48using namespace moveit_servo;
49
50int main(int argc, char* argv[])
51{
52 rclcpp::init(argc, argv);
53
54 // The servo object expects to get a ROS node.
55 const rclcpp::Node::SharedPtr demo_node = std::make_shared<rclcpp::Node>("moveit_servo_demo");
56 moveit::setNodeLoggerName(demo_node->get_name());
57
58 // Get the servo parameters.
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();
63
64 // The publisher to send trajectory message to the robot controller.
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());
68
69 // Create the servo object
70 const planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor =
71 createPlanningSceneMonitor(demo_node, servo_params);
72 Servo servo = Servo(demo_node, servo_param_listener, planning_scene_monitor);
73
74 // Wait for some time, so that the planning scene is loaded in rviz.
75 // This is just for convenience, should not be used for sync in real application.
76 std::this_thread::sleep_for(std::chrono::seconds(3));
77
78 // Get the robot state and joint model group info.
79 auto robot_state = planning_scene_monitor->getStateMonitor()->getCurrentState();
80 const moveit::core::JointModelGroup* joint_model_group =
81 robot_state->getJointModelGroup(servo_params.move_group_name);
82
83 // Set the command type for servo.
84 servo.setCommandType(CommandType::JOINT_JOG);
85
86 // JointJog command that moves only the 7th joint at +0.4 rad/s
87 JointJogCommand joint_jog{ { "panda_joint7" }, { 0.4 } };
88
89 // Frequency at which commands will be sent to the robot controller.
90 rclcpp::WallRate rate(1.0 / servo_params.publish_period);
91
92 std::chrono::seconds timeout_duration(3);
93 std::chrono::seconds time_elapsed(0);
94 const auto start_time = std::chrono::steady_clock::now();
95
96 // create command queue to build trajectory message and add current robot state
97 std::deque<KinematicState> joint_cmd_rolling_window;
98 KinematicState current_state = servo.getCurrentRobotState(true /* wait for updated state */);
99 updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
100
101 RCLCPP_INFO_STREAM(demo_node->get_logger(), servo.getStatusMessage());
102 while (rclcpp::ok())
103 {
104 KinematicState joint_state = servo.getNextJointState(robot_state, joint_jog);
105 const StatusCode status = servo.getStatus();
106
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)
110 {
111 RCLCPP_INFO_STREAM(demo_node->get_logger(), "Timed out");
112 break;
113 }
114 else if (status != StatusCode::INVALID)
115 {
116 updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
117 if (const auto msg = composeTrajectoryMessage(servo_params, joint_cmd_rolling_window))
118 {
119 trajectory_outgoing_cmd_pub->publish(msg.value());
120 }
121 if (!joint_cmd_rolling_window.empty())
122 {
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);
125 }
126 }
127 rate.sleep();
128 }
129
130 RCLCPP_INFO(demo_node->get_logger(), "Exiting demo.");
131 rclcpp::shutdown();
132}
void setCommandType(const CommandType &command_type)
Set the type of incoming servo command.
Definition servo.cpp:332
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...
Definition servo.cpp:644
std::string getStatusMessage() const
Get the message associated with the current servo status.
Definition servo.cpp:322
StatusCode getStatus() const
Get the current status of servo.
Definition servo.cpp:317
KinematicState getNextJointState(const moveit::core::RobotStatePtr &robot_state, const ServoInput &command)
Computes the joint state required to follow the given command.
Definition servo.cpp:470
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...
Definition common.cpp:151
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...
Definition common.cpp:203
planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const servo::Params &servo_params)
Creates the planning scene monitor used by servo.
Definition common.cpp:480
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition logger.cpp:73