Skip to content

Commit 0d2d070

Browse files
pac48sea-bassAndyZe
authored
Add command queue to servo to account for latency (#2594)
* add command queue to servo to account for latency * run pre-commit * fix unsigned compare * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Fix wording Co-authored-by: Sebastian Castro <[email protected]> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <[email protected]> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: Sebastian Castro <[email protected]> * add comments and change variable names * add checks to determine what state information should be published Signed-off-by: Paul Gesel <[email protected]> * change latency parameter name Signed-off-by: Paul Gesel <[email protected]> * factor command queue out of servo instance Signed-off-by: Paul Gesel <[email protected]> * update demos Signed-off-by: Paul Gesel <[email protected]> * needs clean up but working well * deal with duplicate timestamps for sim * add acceleration limiting smoothing * add timeout check in filter Signed-off-by: Paul Gesel <[email protected]> * factor out robot state from servo call Signed-off-by: Paul Gesel <[email protected]> * update comments in smoothing pluin Signed-off-by: Paul Gesel <[email protected]> * fix tests Signed-off-by: Paul Gesel <[email protected]> * change velocity calculation to make interpolation not overshoot Signed-off-by: Paul Gesel <[email protected]> * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: Sebastian Castro <[email protected]> * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Castro <[email protected]> * Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp Co-authored-by: Sebastian Castro <[email protected]> * fix time calculation Signed-off-by: Paul Gesel <[email protected]> * add check to ensure time interval is positive Signed-off-by: Paul Gesel <[email protected]> * simplify demos Signed-off-by: Paul Gesel <[email protected]> * wait for first robot state before starting servo loop Signed-off-by: Paul Gesel <[email protected]> * add comments to acceleration filter Signed-off-by: Paul Gesel <[email protected]> * fix wait time units * fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot. Signed-off-by: Paul Gesel <[email protected]> * add acceleration limit to servo Signed-off-by: Paul Gesel <[email protected]> * remove acceleration filter Signed-off-by: Paul Gesel <[email protected]> * remove other filter files from moveit_core Signed-off-by: Paul Gesel <[email protected]> * add doc string and basic clean up * refactor getRobotState to utils and add a test Signed-off-by: Paul Gesel <[email protected]> * make some things const and fix comments Signed-off-by: Paul Gesel <[email protected]> * use joint_limts params to get robot acceleration limits Signed-off-by: Paul Gesel <[email protected]> * update demo config and set velocities in demos Signed-off-by: Paul Gesel <[email protected]> * fix acceleration calculation Signed-off-by: Paul Gesel <[email protected]> * apply collision_velocity_scale_ in smooth hault, add comments, and rename variables Signed-off-by: Paul Gesel <[email protected]> * use bounds on scaling factors in [0... 1] Signed-off-by: Paul Gesel <[email protected]> * remove joint_acceleration parameter Signed-off-by: Paul Gesel <[email protected]> * add test for jointLimitAccelerationScaling Signed-off-by: Paul Gesel <[email protected]> * refactor velocity and acceleration scaling into common function Signed-off-by: Paul Gesel <[email protected]> * general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc. Signed-off-by: Paul Gesel <[email protected]> * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <[email protected]> * Update moveit_ros/moveit_servo/src/servo.cpp Co-authored-by: AndyZe <[email protected]> * remove override_acceleration_scaling_factor Signed-off-by: Paul Gesel <[email protected]> * fix variable name Signed-off-by: Paul Gesel <[email protected]> * enable use_smoothing in demos Signed-off-by: Paul Gesel <[email protected]> * Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml Co-authored-by: AndyZe <[email protected]> * add current state to command queue if it is empty. This is needed since the time stamp is set in the updateSlidingWindow function now. Signed-off-by: Paul Gesel <[email protected]> * remove acceleration smoothing Signed-off-by: Paul Gesel <[email protected]> * revert jointLimitVelocityScalingFactor refactor Signed-off-by: Paul Gesel <[email protected]> * 1) fix spelling 2) add comments 3) make sure rolling_window always has current state if no command generated 4) fix smooth hault: stop command was not generated if smoothing disabled 5) call resetSmoothing when there are no commands Signed-off-by: Paul Gesel <[email protected]> --------- Signed-off-by: Paul Gesel <[email protected]> Co-authored-by: Sebastian Castro <[email protected]> Co-authored-by: AndyZe <[email protected]>
1 parent 74ba730 commit 0d2d070

19 files changed

+468
-184
lines changed

moveit_ros/moveit_servo/config/panda_simulated_config.yaml

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,11 @@
33
###############################################
44

55
# Optionally override Servo's internal velocity scaling when near singularity or collision (0.0 = use internal velocity scaling)
6-
# override_velocity_scaling_factor = 0.0 # valid range [0.0:1.0]
6+
# override_velocity_scaling_factor = 0.0 # valid range [0.0:1.0]
77

88
## Properties of outgoing commands
9-
publish_period: 0.034 # 1/Nominal publish rate [seconds]
9+
publish_period: 0.01 # 1/Nominal publish rate [seconds]
10+
max_expected_latency: 0.1 # delay between sending a command and the robot executing it [seconds]
1011

1112
command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s
1213
scale:

moveit_ros/moveit_servo/config/servo_parameters.yaml

Lines changed: 16 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,13 +16,24 @@ servo:
1616
publish_period: {
1717
type: double,
1818
read_only: true,
19-
default_value: 0.034,
19+
default_value: 0.01,
2020
description: " 1 / (Nominal publish rate) [seconds]",
2121
validation: {
2222
gt<>: 0.0
2323
}
2424
}
2525

26+
max_expected_latency: {
27+
type: double,
28+
read_only: true,
29+
default_value: 0.1,
30+
description: "Maximum expected latency between generating a servo \
31+
command and the controller receiving it [seconds].",
32+
validation: {
33+
gt<>: 0.0
34+
}
35+
}
36+
2637
move_group_name: {
2738
type: string,
2839
read_only: true,
@@ -325,5 +336,8 @@ servo:
325336
override_velocity_scaling_factor: {
326337
type: double,
327338
default_value: 0.0,
328-
description: "Scaling factor when servo overrides the velocity (eg: near singularities)"
339+
description: "Scaling factor when servo overrides the velocity (eg: near singularities)",
340+
validation: {
341+
bounds<>: [0.0, 1.0]
342+
}
329343
}

moveit_ros/moveit_servo/config/test_config_panda.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ command_out_type: trajectory_msgs/JointTrajectory
2424
# What to publish? Can save some bandwidth as most robots only require positions or velocities
2525
publish_joint_positions: true
2626
publish_joint_velocities: true
27-
publish_joint_accelerations: false
27+
publish_joint_accelerations: true
2828

2929
## Plugins for smoothing outgoing commands
3030
use_smoothing: false

moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp

Lines changed: 24 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,10 +75,16 @@ int main(int argc, char* argv[])
7575
// This is just for convenience, should not be used for sync in real application.
7676
std::this_thread::sleep_for(std::chrono::seconds(3));
7777

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+
7883
// Set the command type for servo.
7984
servo.setCommandType(CommandType::JOINT_JOG);
80-
// JointJog command that moves only the 7th joint at +1.0 rad/s
81-
JointJogCommand joint_jog{ { "panda_joint7" }, { 1.0 } };
85+
86+
// JointJog command that moves only the 7th joint at +0.4 rad/s
87+
JointJogCommand joint_jog{ { "panda_joint7" }, { 0.4 } };
8288

8389
// Frequency at which commands will be sent to the robot controller.
8490
rclcpp::WallRate rate(1.0 / servo_params.publish_period);
@@ -87,10 +93,15 @@ int main(int argc, char* argv[])
8793
std::chrono::seconds time_elapsed(0);
8894
auto start_time = std::chrono::steady_clock::now();
8995

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();
99+
updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
100+
90101
RCLCPP_INFO_STREAM(demo_node->get_logger(), servo.getStatusMessage());
91102
while (rclcpp::ok())
92103
{
93-
const KinematicState joint_state = servo.getNextJointState(joint_jog);
104+
KinematicState joint_state = servo.getNextJointState(robot_state, joint_jog);
94105
const StatusCode status = servo.getStatus();
95106

96107
auto current_time = std::chrono::steady_clock::now();
@@ -102,7 +113,16 @@ int main(int argc, char* argv[])
102113
}
103114
else if (status != StatusCode::INVALID)
104115
{
105-
trajectory_outgoing_cmd_pub->publish(composeTrajectoryMessage(servo_params, joint_state));
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+
}
106126
}
107127
rate.sleep();
108128
}

moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp

Lines changed: 53 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -81,87 +81,91 @@ int main(int argc, char* argv[])
8181
Servo servo = Servo(demo_node, servo_param_listener, planning_scene_monitor);
8282

8383
// Helper function to get the current pose of a specified frame.
84-
const auto get_current_pose = [planning_scene_monitor](const std::string& target_frame) {
85-
return planning_scene_monitor->getStateMonitor()->getCurrentState()->getGlobalLinkTransform(target_frame);
84+
const auto get_current_pose = [](const std::string& target_frame, const moveit::core::RobotStatePtr& robot_state) {
85+
return robot_state->getGlobalLinkTransform(target_frame);
8686
};
8787

8888
// Wait for some time, so that the planning scene is loaded in rviz.
8989
// This is just for convenience, should not be used for sync in real application.
9090
std::this_thread::sleep_for(std::chrono::seconds(3));
9191

92-
// For syncing pose tracking thread and main thread.
93-
std::mutex pose_guard;
94-
std::atomic<bool> stop_tracking = false;
92+
// Get the robot state and joint model group info.
93+
auto robot_state = planning_scene_monitor->getStateMonitor()->getCurrentState();
94+
const moveit::core::JointModelGroup* joint_model_group =
95+
robot_state->getJointModelGroup(servo_params.move_group_name);
9596

9697
// Set the command type for servo.
9798
servo.setCommandType(CommandType::POSE);
9899

99100
// The dynamically updated target pose.
100101
PoseCommand target_pose;
101102
target_pose.frame_id = K_BASE_FRAME;
102-
// Initializing the target pose as end effector pose, this can be any pose.
103-
target_pose.pose = get_current_pose(K_TIP_FRAME);
104-
105-
// The pose tracking lambda that will be run in a separate thread.
106-
auto pose_tracker = [&]() {
107-
KinematicState joint_state;
108-
rclcpp::WallRate tracking_rate(1 / servo_params.publish_period);
109-
while (!stop_tracking && rclcpp::ok())
110-
{
111-
{
112-
std::lock_guard<std::mutex> pguard(pose_guard);
113-
joint_state = servo.getNextJointState(target_pose);
114-
}
115-
StatusCode status = servo.getStatus();
116-
if (status != StatusCode::INVALID)
117-
trajectory_outgoing_cmd_pub->publish(composeTrajectoryMessage(servo_params, joint_state));
118103

119-
tracking_rate.sleep();
120-
}
121-
};
104+
// Initializing the target pose as end effector pose, this can be any pose.
105+
target_pose.pose = get_current_pose(K_TIP_FRAME, robot_state);
122106

123-
// Pose tracking thread will exit upon reaching this pose.
107+
// servo loop will exit upon reaching this pose.
124108
Eigen::Isometry3d terminal_pose = target_pose.pose;
125109
terminal_pose.rotate(Eigen::AngleAxisd(M_PI / 4, Eigen::Vector3d::UnitZ()));
126110
terminal_pose.translate(Eigen::Vector3d(0.0, 0.0, -0.1));
127111

128-
std::thread tracker_thread(pose_tracker);
129-
tracker_thread.detach();
130-
131112
// The target pose (frame being tracked) moves by this step size each iteration.
132-
Eigen::Vector3d linear_step_size{ 0.0, 0.0, -0.002 };
113+
Eigen::Vector3d linear_step_size{ 0.0, 0.0, -0.001 };
133114
Eigen::AngleAxisd angular_step_size(0.01, Eigen::Vector3d::UnitZ());
134115

135-
// Frequency at which commands will be sent to the robot controller.
136-
rclcpp::WallRate command_rate(50);
137116
RCLCPP_INFO_STREAM(demo_node->get_logger(), servo.getStatusMessage());
138117

118+
rclcpp::WallRate servo_rate(1 / servo_params.publish_period);
119+
120+
// create command queue to build trajectory message and add current robot state
121+
std::deque<KinematicState> joint_cmd_rolling_window;
122+
KinematicState current_state = servo.getCurrentRobotState();
123+
updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
124+
125+
bool satisfies_linear_tolerance = false;
126+
bool satisfies_angular_tolerance = false;
127+
bool stop_tracking = false;
139128
while (!stop_tracking && rclcpp::ok())
140129
{
130+
// check if goal reached
131+
target_pose.pose = get_current_pose(K_TIP_FRAME, robot_state);
132+
satisfies_linear_tolerance |= target_pose.pose.translation().isApprox(terminal_pose.translation(),
133+
servo_params.pose_tracking.linear_tolerance);
134+
satisfies_angular_tolerance |=
135+
target_pose.pose.rotation().isApprox(terminal_pose.rotation(), servo_params.pose_tracking.angular_tolerance);
136+
stop_tracking = satisfies_linear_tolerance && satisfies_angular_tolerance;
137+
138+
// Dynamically update the target pose.
139+
if (!satisfies_linear_tolerance)
141140
{
142-
std::lock_guard<std::mutex> pguard(pose_guard);
143-
target_pose.pose = get_current_pose(K_TIP_FRAME);
144-
const bool satisfies_linear_tolerance = target_pose.pose.translation().isApprox(
145-
terminal_pose.translation(), servo_params.pose_tracking.linear_tolerance);
146-
const bool satisfies_angular_tolerance =
147-
target_pose.pose.rotation().isApprox(terminal_pose.rotation(), servo_params.pose_tracking.angular_tolerance);
148-
stop_tracking = satisfies_linear_tolerance && satisfies_angular_tolerance;
149-
// Dynamically update the target pose.
150-
if (!satisfies_linear_tolerance)
151-
target_pose.pose.translate(linear_step_size);
152-
if (!satisfies_angular_tolerance)
153-
target_pose.pose.rotate(angular_step_size);
141+
target_pose.pose.translate(linear_step_size);
142+
}
143+
if (!satisfies_angular_tolerance)
144+
{
145+
target_pose.pose.rotate(angular_step_size);
154146
}
155147

156-
command_rate.sleep();
148+
// get next servo command
149+
KinematicState joint_state = servo.getNextJointState(robot_state, target_pose);
150+
StatusCode status = servo.getStatus();
151+
if (status != StatusCode::INVALID)
152+
{
153+
updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
154+
if (const auto msg = composeTrajectoryMessage(servo_params, joint_cmd_rolling_window))
155+
{
156+
trajectory_outgoing_cmd_pub->publish(msg.value());
157+
}
158+
if (!joint_cmd_rolling_window.empty())
159+
{
160+
robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
161+
robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
162+
}
163+
}
164+
165+
servo_rate.sleep();
157166
}
158167

159168
RCLCPP_INFO_STREAM(demo_node->get_logger(), "REACHED : " << stop_tracking);
160-
stop_tracking = true;
161-
162-
if (tracker_thread.joinable())
163-
tracker_thread.join();
164-
165169
RCLCPP_INFO(demo_node->get_logger(), "Exiting demo.");
166170
rclcpp::shutdown();
167171
}

moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp

Lines changed: 25 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -77,24 +77,34 @@ int main(int argc, char* argv[])
7777
// This is just for convenience, should not be used for sync in real application.
7878
std::this_thread::sleep_for(std::chrono::seconds(3));
7979

80+
// Get the robot state and joint model group info.
81+
auto robot_state = planning_scene_monitor->getStateMonitor()->getCurrentState();
82+
const moveit::core::JointModelGroup* joint_model_group =
83+
robot_state->getJointModelGroup(servo_params.move_group_name);
84+
8085
// Set the command type for servo.
8186
servo.setCommandType(CommandType::TWIST);
8287

83-
// Move end effector in the +z direction at 10 cm/s
84-
// while turning around z axis in the +ve direction at 0.5 rad/s
85-
TwistCommand target_twist{ "panda_link0", { 0.0, 0.0, 0.1, 0.0, 0.0, 0.5 } };
88+
// Move end effector in the +z direction at 5 cm/s
89+
// while turning around z axis in the +ve direction at 0.4 rad/s
90+
TwistCommand target_twist{ "panda_link0", { 0.0, 0.0, 0.05, 0.0, 0.0, 0.4 } };
8691

8792
// Frequency at which commands will be sent to the robot controller.
8893
rclcpp::WallRate rate(1.0 / servo_params.publish_period);
8994

90-
std::chrono::seconds timeout_duration(5);
95+
std::chrono::seconds timeout_duration(4);
9196
std::chrono::seconds time_elapsed(0);
9297
auto start_time = std::chrono::steady_clock::now();
9398

99+
// create command queue to build trajectory message and add current robot state
100+
std::deque<KinematicState> joint_cmd_rolling_window;
101+
KinematicState current_state = servo.getCurrentRobotState();
102+
updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
103+
94104
RCLCPP_INFO_STREAM(demo_node->get_logger(), servo.getStatusMessage());
95105
while (rclcpp::ok())
96106
{
97-
const KinematicState joint_state = servo.getNextJointState(target_twist);
107+
KinematicState joint_state = servo.getNextJointState(robot_state, target_twist);
98108
const StatusCode status = servo.getStatus();
99109

100110
auto current_time = std::chrono::steady_clock::now();
@@ -106,7 +116,16 @@ int main(int argc, char* argv[])
106116
}
107117
else if (status != StatusCode::INVALID)
108118
{
109-
trajectory_outgoing_cmd_pub->publish(composeTrajectoryMessage(servo_params, joint_state));
119+
updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
120+
if (const auto msg = composeTrajectoryMessage(servo_params, joint_cmd_rolling_window))
121+
{
122+
trajectory_outgoing_cmd_pub->publish(msg.value());
123+
}
124+
if (!joint_cmd_rolling_window.empty())
125+
{
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);
128+
}
110129
}
111130
rate.sleep();
112131
}

moveit_ros/moveit_servo/include/moveit_servo/servo.hpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@
5454
#include <tf2_ros/transform_listener.h>
5555
#include <variant>
5656
#include <rclcpp/logger.hpp>
57+
#include <queue>
5758

5859
namespace moveit_servo
5960
{
@@ -74,10 +75,11 @@ class Servo
7475

7576
/**
7677
* \brief Computes the joint state required to follow the given command.
78+
* @param robot_state RobotStatePtr instance used for calculating the next joint state.
7779
* @param command The command to follow, std::variant type, can handle JointJog, Twist and Pose.
7880
* @return The required joint state.
7981
*/
80-
KinematicState getNextJointState(const ServoInput& command);
82+
KinematicState getNextJointState(const moveit::core::RobotStatePtr& robot_state, const ServoInput& command);
8183

8284
/**
8385
* \brief Set the type of incoming servo command.
@@ -122,7 +124,7 @@ class Servo
122124

123125
/**
124126
* \brief Smoothly halt at a commanded state when command goes stale.
125-
* @param The last commanded joint states.
127+
* @param halt_state The desired stop state.
126128
* @return The next state stepping towards the required halting state.
127129
*/
128130
std::pair<bool, KinematicState> smoothHalt(const KinematicState& halt_state);
@@ -175,15 +177,11 @@ class Servo
175177
/**
176178
* \brief Compute the change in joint position required to follow the received command.
177179
* @param command The incoming servo command.
180+
* @param robot_state RobotStatePtr instance used for calculating the command.
178181
* @return The joint position change required (delta).
179182
*/
180183
Eigen::VectorXd jointDeltaFromCommand(const ServoInput& command, const moveit::core::RobotStatePtr& robot_state);
181184

182-
/**
183-
* \brief Updates data depending on joint model group
184-
*/
185-
void updateJointModelGroup();
186-
187185
/**
188186
* \brief Validate the servo parameters
189187
* @param servo_params The servo parameters

moveit_ros/moveit_servo/include/moveit_servo/servo_node.hpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -99,9 +99,9 @@ class ServoNode
9999
void twistCallback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg);
100100
void poseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg);
101101

102-
std::optional<KinematicState> processJointJogCommand();
103-
std::optional<KinematicState> processTwistCommand();
104-
std::optional<KinematicState> processPoseCommand();
102+
std::optional<KinematicState> processJointJogCommand(const moveit::core::RobotStatePtr& robot_state);
103+
std::optional<KinematicState> processTwistCommand(const moveit::core::RobotStatePtr& robot_state);
104+
std::optional<KinematicState> processPoseCommand(const moveit::core::RobotStatePtr& robot_state);
105105

106106
// Variables
107107

@@ -132,6 +132,9 @@ class ServoNode
132132

133133
// Threads used by ServoNode
134134
std::thread servo_loop_thread_;
135+
136+
// rolling window of joint commands
137+
std::deque<KinematicState> joint_cmd_rolling_window_;
135138
};
136139

137140
} // namespace moveit_servo

0 commit comments

Comments
 (0)