Skip to content

Commit 7d3693b

Browse files
sea-basssjahr
andauthored
[Servo] Use velocity scaling properly in Cartesian and pose tracking commands (moveit#3007)
* [Servo] Use velocity scaling properly in Cartesian and pose tracking commands * Tweak tests * Update moveit_ros/moveit_servo/config/servo_parameters.yaml Co-authored-by: Sebastian Jahr <[email protected]> * Tweak configs * Reduce joint velocity and delay in tests * Reduce scalings * Fix expected value with lower speeds * Coding from your phone is a bad idea * Update expected values and tolerances * Protect against division by zero * More time before integration test starts --------- Co-authored-by: Sebastian Jahr <[email protected]>
1 parent 489d996 commit 7d3693b

File tree

8 files changed

+88
-37
lines changed

8 files changed

+88
-37
lines changed

moveit_ros/moveit_servo/config/panda_simulated_config.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ publish_joint_accelerations: false
2828

2929
## Plugins for smoothing outgoing commands
3030
use_smoothing: true
31-
smoothing_filter_plugin_name: "online_signal_smoothing::RuckigFilterPlugin"
31+
smoothing_filter_plugin_name: "online_signal_smoothing::AccelerationLimitedPlugin"
3232

3333
# If is_primary_planning_scene_monitor is set to true, the Servo server's PlanningScene advertises the /get_planning_scene service,
3434
# which other nodes can use as a source for information about the planning environment.

moveit_ros/moveit_servo/config/servo_parameters.yaml

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -86,24 +86,23 @@ servo:
8686
linear: {
8787
type: double,
8888
default_value: 0.4,
89-
description: "Max linear velocity. Unit is [m/s]. Only used for Cartesian commands."
89+
description: "Max linear velocity in m/s if using speed units or tracking a pose, else a scaling factor on the unitless commanded velocity. Used for Cartesian and pose tracking commands."
9090
}
9191
rotational: {
9292
type: double,
9393
default_value: 0.8,
94-
description: "Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands."
94+
description: "Max angular velocity in rad/s if using speed units or tracking a pose, else a scaling factor on the unitless commanded velocity. Used for Cartesian and pose tracking commands."
9595
}
9696
joint: {
9797
type: double,
9898
default_value: 0.5,
99-
description: "Max joint angular/linear velocity. Only used for joint commands on joint_command_in_topic."
99+
description: "Joint angular/linear velocity scale. Only used for unitless joint commands."
100100
}
101101

102-
103102
incoming_command_timeout: {
104103
type: double,
105104
default_value: 0.1,
106-
description: "Commands will be discarded if it is older than the timeout.\
105+
description: "Commands will be discarded if they are older than the timeout, in seconds.\
107106
Important because ROS may drop some messages."
108107
}
109108

@@ -123,7 +122,7 @@ servo:
123122
linear_tolerance: {
124123
type: double,
125124
default_value: 0.001,
126-
description: "The allowable linear error when tracking a pose.",
125+
description: "The allowable linear error, in meters, when tracking a pose.",
127126
validation: {
128127
gt<>: 0.0
129128
}
@@ -132,7 +131,7 @@ servo:
132131
angular_tolerance: {
133132
type: double,
134133
default_value: 0.01,
135-
description: "The allowable angular error when tracking a pose.",
134+
description: "The allowable angular error, in radians, when tracking a pose.",
136135
validation: {
137136
gt<>: 0.0
138137
}

moveit_ros/moveit_servo/config/test_config_panda.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@ incoming_command_timeout: 0.5 # seconds
1212
command_in_type: "unitless" # "unitless" in the range [-1:1], as if from joystick. "speed_units" cmds are in m/s and rad/s
1313
scale:
1414
# Scale parameters are only used if command_in_type=="unitless"
15-
linear: 1.0 # Max linear velocity. Unit is [m/s]. Only used for Cartesian commands.
16-
rotational: 1.0 # Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands.
15+
linear: 0.2 # Max linear velocity. Unit is [m/s]. Only used for Cartesian commands.
16+
rotational: 0.2 # Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands.
1717
# Max joint angular/linear velocity. Only used for joint commands on joint_command_in_topic.
18-
joint: 1.0
18+
joint: 0.5
1919

2020
# What type of topic does your robot driver expect?
2121
# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory
@@ -56,7 +56,7 @@ status_topic: ~/status # Publish status to this topic
5656
command_out_topic: /panda_arm_controller/joint_trajectory # Publish outgoing commands here
5757

5858
## Collision checking for the entire robot body
59-
check_collisions: true # Check collisions?
59+
check_collisions: true # Check collisions?
6060
collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
6161
self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m]
6262
scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]

moveit_ros/moveit_servo/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545
<exec_depend>joy</exec_depend>
4646
<exec_depend>launch_param_builder</exec_depend>
4747
<exec_depend>moveit_configs_utils</exec_depend>
48+
<exec_depend>moveit_ros_visualization</exec_depend>
4849
<exec_depend>robot_state_publisher</exec_depend>
4950
<exec_depend>tf2_ros</exec_depend>
5051

moveit_ros/moveit_servo/src/utils/command.cpp

Lines changed: 57 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -159,7 +159,7 @@ JointDeltaResult jointDeltaFromTwist(const TwistCommand& command, const moveit::
159159
const bool is_zero = command.velocities.isZero();
160160
if (!is_zero && is_planning_frame && valid_command)
161161
{
162-
// Compute the Cartesian position delta based on incoming command, assumed to be in m/s
162+
// Compute the Cartesian position delta based on incoming twist command.
163163
cartesian_position_delta = command.velocities * servo_params.publish_period;
164164
// This scaling is supposed to be applied to the command.
165165
// But since it is only used here, we avoid creating a copy of the command,
@@ -169,6 +169,25 @@ JointDeltaResult jointDeltaFromTwist(const TwistCommand& command, const moveit::
169169
cartesian_position_delta.head<3>() *= servo_params.scale.linear;
170170
cartesian_position_delta.tail<3>() *= servo_params.scale.rotational;
171171
}
172+
else if (servo_params.command_in_type == "speed_units")
173+
{
174+
if (servo_params.scale.linear > 0.0)
175+
{
176+
const auto linear_speed_scale = command.velocities.head<3>().norm() / servo_params.scale.linear;
177+
if (linear_speed_scale > 1.0)
178+
{
179+
cartesian_position_delta.head<3>() /= linear_speed_scale;
180+
}
181+
}
182+
if (servo_params.scale.rotational > 0.0)
183+
{
184+
const auto angular_speed_scale = command.velocities.tail<3>().norm() / servo_params.scale.rotational;
185+
if (angular_speed_scale > 1.0)
186+
{
187+
cartesian_position_delta.tail<3>() /= angular_speed_scale;
188+
}
189+
}
190+
}
172191

173192
// Compute the required change in joint angles.
174193
const auto delta_result =
@@ -178,7 +197,7 @@ JointDeltaResult jointDeltaFromTwist(const TwistCommand& command, const moveit::
178197
{
179198
joint_position_delta = delta_result.second;
180199
// Get velocity scaling information for singularity.
181-
const std::pair<double, StatusCode> singularity_scaling_info =
200+
const auto singularity_scaling_info =
182201
velocityScalingFactorForSingularity(robot_state, cartesian_position_delta, servo_params);
183202
// Apply velocity scaling for singularity, if there was any scaling.
184203
if (singularity_scaling_info.second != StatusCode::NO_WARNING)
@@ -227,11 +246,33 @@ JointDeltaResult jointDeltaFromPose(const PoseCommand& command, const moveit::co
227246

228247
// Compute linear and angular change needed.
229248
const Eigen::Isometry3d ee_pose{ robot_state->getGlobalLinkTransform(ee_frame) };
230-
const Eigen::Quaterniond q_current(ee_pose.rotation()), q_target(command.pose.rotation());
231-
const Eigen::Quaterniond q_error = q_target * q_current.inverse();
232-
const Eigen::AngleAxisd angle_axis_error(q_error);
249+
const Eigen::Quaterniond q_current(ee_pose.rotation());
250+
Eigen::Quaterniond q_target(command.pose.rotation());
251+
Eigen::Vector3d translation_error = command.pose.translation() - ee_pose.translation();
252+
253+
// Limit the commands by the maximum linear and angular speeds provided.
254+
if (servo_params.scale.linear > 0.0)
255+
{
256+
const auto linear_speed_scale =
257+
(translation_error.norm() / servo_params.publish_period) / servo_params.scale.linear;
258+
if (linear_speed_scale > 1.0)
259+
{
260+
translation_error /= linear_speed_scale;
261+
}
262+
}
263+
if (servo_params.scale.rotational > 0.0)
264+
{
265+
const auto angular_speed_scale =
266+
(std::abs(q_target.angularDistance(q_current)) / servo_params.publish_period) / servo_params.scale.rotational;
267+
if (angular_speed_scale > 1.0)
268+
{
269+
q_target = q_current.slerp(1.0 / angular_speed_scale, q_target);
270+
}
271+
}
233272

234-
cartesian_position_delta.head<3>() = command.pose.translation() - ee_pose.translation();
273+
// Compute the Cartesian deltas from the velocity-scaled values.
274+
const auto angle_axis_error = Eigen::AngleAxisd(q_target * q_current.inverse());
275+
cartesian_position_delta.head<3>() = translation_error;
235276
cartesian_position_delta.tail<3>() = angle_axis_error.axis() * angle_axis_error.angle();
236277

237278
// Compute the required change in joint angles.
@@ -241,6 +282,16 @@ JointDeltaResult jointDeltaFromPose(const PoseCommand& command, const moveit::co
241282
if (status != StatusCode::INVALID)
242283
{
243284
joint_position_delta = delta_result.second;
285+
// Get velocity scaling information for singularity.
286+
const auto singularity_scaling_info =
287+
velocityScalingFactorForSingularity(robot_state, cartesian_position_delta, servo_params);
288+
// Apply velocity scaling for singularity, if there was any scaling.
289+
if (singularity_scaling_info.second != StatusCode::NO_WARNING)
290+
{
291+
status = singularity_scaling_info.second;
292+
RCLCPP_WARN_STREAM(getLogger(), SERVO_STATUS_CODE_MAP.at(status));
293+
joint_position_delta *= singularity_scaling_info.first;
294+
}
244295
}
245296
}
246297
else

moveit_ros/moveit_servo/tests/launch/servo_cpp_integration.test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@ def generate_test_description():
112112
joint_state_broadcaster_spawner,
113113
panda_arm_controller_spawner,
114114
test_container,
115-
launch.actions.TimerAction(period=2.0, actions=[servo_gtest]),
115+
launch.actions.TimerAction(period=5.0, actions=[servo_gtest]),
116116
launch_testing.actions.ReadyToTest(),
117117
]
118118
), {

moveit_ros/moveit_servo/tests/test_integration.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,8 @@ TEST_F(ServoCppFixture, JointJogTest)
6666

6767
// Check against manually verified value
6868
double delta = next_state.positions[6] - curr_state.positions[6];
69-
constexpr double tol = 0.00001;
70-
ASSERT_NEAR(delta, 0.02, tol);
69+
constexpr double tol = 1.0e-5;
70+
ASSERT_NEAR(delta, 0.01, tol);
7171
}
7272

7373
TEST_F(ServoCppFixture, TwistTest)
@@ -89,9 +89,9 @@ TEST_F(ServoCppFixture, TwistTest)
8989
ASSERT_EQ(status_next, moveit_servo::StatusCode::NO_WARNING);
9090

9191
// Check against manually verified value
92-
constexpr double expected_delta = -0.001693;
92+
constexpr double expected_delta = -0.000338;
9393
double delta = next_state.positions[6] - curr_state.positions[6];
94-
constexpr double tol = 0.00001;
94+
constexpr double tol = 1.0e-5;
9595
ASSERT_NEAR(delta, expected_delta, tol);
9696
}
9797

@@ -114,9 +114,9 @@ TEST_F(ServoCppFixture, NonPlanningFrameTwistTest)
114114
ASSERT_EQ(status_next, moveit_servo::StatusCode::NO_WARNING);
115115

116116
// Check against manually verified value
117-
constexpr double expected_delta = 0.001693;
117+
constexpr double expected_delta = 0.000338;
118118
double delta = next_state.positions[6] - curr_state.positions[6];
119-
constexpr double tol = 0.00001;
119+
constexpr double tol = 1.0e-5;
120120
ASSERT_NEAR(delta, expected_delta, tol);
121121
}
122122

@@ -145,9 +145,9 @@ TEST_F(ServoCppFixture, PoseTest)
145145
ASSERT_EQ(status_next, moveit_servo::StatusCode::NO_WARNING);
146146

147147
// Check against manually verified value
148-
constexpr double expected_delta = 0.057420;
148+
constexpr double expected_delta = 0.003364;
149149
double delta = next_state.positions[6] - curr_state.positions[6];
150-
constexpr double tol = 0.00001;
150+
constexpr double tol = 1.0e-5;
151151
ASSERT_NEAR(delta, expected_delta, tol);
152152
}
153153

moveit_ros/moveit_servo/tests/test_ros_integration.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -90,15 +90,15 @@ TEST_F(ServoRosFixture, testJointJog)
9090

9191
std::fill(jog_cmd.velocities.begin(), jog_cmd.velocities.end(), 0.0);
9292

93-
jog_cmd.velocities[6] = 1.0;
93+
jog_cmd.velocities[6] = 0.5;
9494

9595
size_t count = 0;
9696
while (rclcpp::ok() && count < NUM_COMMANDS)
9797
{
9898
jog_cmd.header.stamp = servo_test_node_->now();
9999
joint_jog_publisher->publish(jog_cmd);
100100
count++;
101-
rclcpp::sleep_for(std::chrono::milliseconds(200));
101+
rclcpp::sleep_for(std::chrono::milliseconds(100));
102102
}
103103

104104
ASSERT_GE(traj_count_, NUM_COMMANDS);
@@ -137,7 +137,7 @@ TEST_F(ServoRosFixture, testTwist)
137137
twist_cmd.header.stamp = servo_test_node_->now();
138138
twist_publisher->publish(twist_cmd);
139139
count++;
140-
rclcpp::sleep_for(std::chrono::milliseconds(200));
140+
rclcpp::sleep_for(std::chrono::milliseconds(100));
141141
}
142142

143143
ASSERT_GE(traj_count_, NUM_COMMANDS);
@@ -162,13 +162,13 @@ TEST_F(ServoRosFixture, testPose)
162162
geometry_msgs::msg::PoseStamped pose_cmd;
163163
pose_cmd.header.frame_id = "panda_link0"; // Planning frame
164164

165-
pose_cmd.pose.position.x = 0.3;
166-
pose_cmd.pose.position.y = 0.0;
165+
pose_cmd.pose.position.x = 0.2;
166+
pose_cmd.pose.position.y = -0.2;
167167
pose_cmd.pose.position.z = 0.6;
168-
pose_cmd.pose.orientation.x = 0.7;
169-
pose_cmd.pose.orientation.y = -0.7;
170-
pose_cmd.pose.orientation.z = -0.000014;
171-
pose_cmd.pose.orientation.w = -0.0000015;
168+
pose_cmd.pose.orientation.x = 0.7071;
169+
pose_cmd.pose.orientation.y = -0.7071;
170+
pose_cmd.pose.orientation.z = 0.0;
171+
pose_cmd.pose.orientation.w = 0.0;
172172

173173
ASSERT_NE(state_count_, 0);
174174

@@ -178,7 +178,7 @@ TEST_F(ServoRosFixture, testPose)
178178
pose_cmd.header.stamp = servo_test_node_->now();
179179
pose_publisher->publish(pose_cmd);
180180
count++;
181-
rclcpp::sleep_for(std::chrono::milliseconds(200));
181+
rclcpp::sleep_for(std::chrono::milliseconds(100));
182182
}
183183

184184
ASSERT_GE(traj_count_, NUM_COMMANDS);

0 commit comments

Comments
 (0)