Skip to content

Commit

Permalink
Add command queue to servo to account for latency (#2594)
Browse files Browse the repository at this point in the history
* 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 <4603398+sea-bass@users.noreply.github.com>

* Update moveit_ros/moveit_servo/src/servo.cpp

Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

* Update moveit_ros/moveit_servo/src/servo.cpp

Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

* add comments and change variable names

* add checks to determine what state information should be published

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* change latency parameter name

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* factor command queue out of servo instance

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* update demos

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* 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 <paulgesel@gmail.com>

* factor out robot state from servo call

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* update comments in smoothing pluin

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* fix tests

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* change velocity calculation to make interpolation not overshoot

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml

Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

* Update moveit_ros/moveit_servo/config/servo_parameters.yaml

Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

* Update moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp

Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>

* fix time calculation

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* add check to ensure time interval is positive

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* simplify demos

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* wait for first robot state before starting servo loop

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* add comments to acceleration filter

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* fix wait time units

* fix logic bug in smoothHalt and remove stopping point from trajectory message. Still some overshoot.

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* add acceleration limit to servo

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* remove acceleration filter

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* remove other filter files from moveit_core

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* add doc string and basic clean up

* refactor getRobotState to utils and add a test

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* make some things const and fix comments

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* use joint_limts params to get robot acceleration limits

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* update demo config and set velocities in demos

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* fix acceleration calculation

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* apply collision_velocity_scale_ in smooth hault, add comments, and rename variables

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* use bounds on scaling factors in [0... 1]

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* remove joint_acceleration parameter

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* add test for jointLimitAccelerationScaling

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* refactor velocity and acceleration scaling into common function

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* general clean up, add comments, fix parameters, set timestamp in updateSlidingWindow, etc.

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml

Co-authored-by: AndyZe <andyz@utexas.edu>

* Update moveit_ros/moveit_servo/src/servo.cpp

Co-authored-by: AndyZe <andyz@utexas.edu>

* remove override_acceleration_scaling_factor

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* fix variable name

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* enable use_smoothing in demos

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* Update moveit_ros/moveit_servo/config/panda_simulated_config.yaml

Co-authored-by: AndyZe <andyz@utexas.edu>

* 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 <paulgesel@gmail.com>

* remove acceleration smoothing

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* revert jointLimitVelocityScalingFactor refactor

Signed-off-by: Paul Gesel <paulgesel@gmail.com>

* 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 <paulgesel@gmail.com>

---------

Signed-off-by: Paul Gesel <paulgesel@gmail.com>
Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com>
Co-authored-by: AndyZe <andyz@utexas.edu>
  • Loading branch information
3 people authored Jan 3, 2024
1 parent 74ba730 commit 0d2d070
Show file tree
Hide file tree
Showing 19 changed files with 468 additions and 184 deletions.
5 changes: 3 additions & 2 deletions moveit_ros/moveit_servo/config/panda_simulated_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,11 @@
###############################################

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

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

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
scale:
Expand Down
18 changes: 16 additions & 2 deletions moveit_ros/moveit_servo/config/servo_parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,24 @@ servo:
publish_period: {
type: double,
read_only: true,
default_value: 0.034,
default_value: 0.01,
description: " 1 / (Nominal publish rate) [seconds]",
validation: {
gt<>: 0.0
}
}

max_expected_latency: {
type: double,
read_only: true,
default_value: 0.1,
description: "Maximum expected latency between generating a servo \
command and the controller receiving it [seconds].",
validation: {
gt<>: 0.0
}
}

move_group_name: {
type: string,
read_only: true,
Expand Down Expand Up @@ -325,5 +336,8 @@ servo:
override_velocity_scaling_factor: {
type: double,
default_value: 0.0,
description: "Scaling factor when servo overrides the velocity (eg: near singularities)"
description: "Scaling factor when servo overrides the velocity (eg: near singularities)",
validation: {
bounds<>: [0.0, 1.0]
}
}
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/config/test_config_panda.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ command_out_type: trajectory_msgs/JointTrajectory
# What to publish? Can save some bandwidth as most robots only require positions or velocities
publish_joint_positions: true
publish_joint_velocities: true
publish_joint_accelerations: false
publish_joint_accelerations: true

## Plugins for smoothing outgoing commands
use_smoothing: false
Expand Down
28 changes: 24 additions & 4 deletions moveit_ros/moveit_servo/demos/cpp_interface/demo_joint_jog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,10 +75,16 @@ int main(int argc, char* argv[])
// This is just for convenience, should not be used for sync in real application.
std::this_thread::sleep_for(std::chrono::seconds(3));

// Get the robot state and joint model group info.
auto robot_state = planning_scene_monitor->getStateMonitor()->getCurrentState();
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params.move_group_name);

// Set the command type for servo.
servo.setCommandType(CommandType::JOINT_JOG);
// JointJog command that moves only the 7th joint at +1.0 rad/s
JointJogCommand joint_jog{ { "panda_joint7" }, { 1.0 } };

// JointJog command that moves only the 7th joint at +0.4 rad/s
JointJogCommand joint_jog{ { "panda_joint7" }, { 0.4 } };

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

// create command queue to build trajectory message and add current robot state
std::deque<KinematicState> joint_cmd_rolling_window;
KinematicState current_state = servo.getCurrentRobotState();
updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());

RCLCPP_INFO_STREAM(demo_node->get_logger(), servo.getStatusMessage());
while (rclcpp::ok())
{
const KinematicState joint_state = servo.getNextJointState(joint_jog);
KinematicState joint_state = servo.getNextJointState(robot_state, joint_jog);
const StatusCode status = servo.getStatus();

auto current_time = std::chrono::steady_clock::now();
Expand All @@ -102,7 +113,16 @@ int main(int argc, char* argv[])
}
else if (status != StatusCode::INVALID)
{
trajectory_outgoing_cmd_pub->publish(composeTrajectoryMessage(servo_params, joint_state));
updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
if (const auto msg = composeTrajectoryMessage(servo_params, joint_cmd_rolling_window))
{
trajectory_outgoing_cmd_pub->publish(msg.value());
}
if (!joint_cmd_rolling_window.empty())
{
robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
}
}
rate.sleep();
}
Expand Down
102 changes: 53 additions & 49 deletions moveit_ros/moveit_servo/demos/cpp_interface/demo_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,87 +81,91 @@ int main(int argc, char* argv[])
Servo servo = Servo(demo_node, servo_param_listener, planning_scene_monitor);

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

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

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

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

// The dynamically updated target pose.
PoseCommand target_pose;
target_pose.frame_id = K_BASE_FRAME;
// Initializing the target pose as end effector pose, this can be any pose.
target_pose.pose = get_current_pose(K_TIP_FRAME);

// The pose tracking lambda that will be run in a separate thread.
auto pose_tracker = [&]() {
KinematicState joint_state;
rclcpp::WallRate tracking_rate(1 / servo_params.publish_period);
while (!stop_tracking && rclcpp::ok())
{
{
std::lock_guard<std::mutex> pguard(pose_guard);
joint_state = servo.getNextJointState(target_pose);
}
StatusCode status = servo.getStatus();
if (status != StatusCode::INVALID)
trajectory_outgoing_cmd_pub->publish(composeTrajectoryMessage(servo_params, joint_state));

tracking_rate.sleep();
}
};
// Initializing the target pose as end effector pose, this can be any pose.
target_pose.pose = get_current_pose(K_TIP_FRAME, robot_state);

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

std::thread tracker_thread(pose_tracker);
tracker_thread.detach();

// The target pose (frame being tracked) moves by this step size each iteration.
Eigen::Vector3d linear_step_size{ 0.0, 0.0, -0.002 };
Eigen::Vector3d linear_step_size{ 0.0, 0.0, -0.001 };
Eigen::AngleAxisd angular_step_size(0.01, Eigen::Vector3d::UnitZ());

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

rclcpp::WallRate servo_rate(1 / servo_params.publish_period);

// create command queue to build trajectory message and add current robot state
std::deque<KinematicState> joint_cmd_rolling_window;
KinematicState current_state = servo.getCurrentRobotState();
updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());

bool satisfies_linear_tolerance = false;
bool satisfies_angular_tolerance = false;
bool stop_tracking = false;
while (!stop_tracking && rclcpp::ok())
{
// check if goal reached
target_pose.pose = get_current_pose(K_TIP_FRAME, robot_state);
satisfies_linear_tolerance |= target_pose.pose.translation().isApprox(terminal_pose.translation(),
servo_params.pose_tracking.linear_tolerance);
satisfies_angular_tolerance |=
target_pose.pose.rotation().isApprox(terminal_pose.rotation(), servo_params.pose_tracking.angular_tolerance);
stop_tracking = satisfies_linear_tolerance && satisfies_angular_tolerance;

// Dynamically update the target pose.
if (!satisfies_linear_tolerance)
{
std::lock_guard<std::mutex> pguard(pose_guard);
target_pose.pose = get_current_pose(K_TIP_FRAME);
const bool satisfies_linear_tolerance = target_pose.pose.translation().isApprox(
terminal_pose.translation(), servo_params.pose_tracking.linear_tolerance);
const bool satisfies_angular_tolerance =
target_pose.pose.rotation().isApprox(terminal_pose.rotation(), servo_params.pose_tracking.angular_tolerance);
stop_tracking = satisfies_linear_tolerance && satisfies_angular_tolerance;
// Dynamically update the target pose.
if (!satisfies_linear_tolerance)
target_pose.pose.translate(linear_step_size);
if (!satisfies_angular_tolerance)
target_pose.pose.rotate(angular_step_size);
target_pose.pose.translate(linear_step_size);
}
if (!satisfies_angular_tolerance)
{
target_pose.pose.rotate(angular_step_size);
}

command_rate.sleep();
// get next servo command
KinematicState joint_state = servo.getNextJointState(robot_state, target_pose);
StatusCode status = servo.getStatus();
if (status != StatusCode::INVALID)
{
updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
if (const auto msg = composeTrajectoryMessage(servo_params, joint_cmd_rolling_window))
{
trajectory_outgoing_cmd_pub->publish(msg.value());
}
if (!joint_cmd_rolling_window.empty())
{
robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
}
}

servo_rate.sleep();
}

RCLCPP_INFO_STREAM(demo_node->get_logger(), "REACHED : " << stop_tracking);
stop_tracking = true;

if (tracker_thread.joinable())
tracker_thread.join();

RCLCPP_INFO(demo_node->get_logger(), "Exiting demo.");
rclcpp::shutdown();
}
31 changes: 25 additions & 6 deletions moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,24 +77,34 @@ int main(int argc, char* argv[])
// This is just for convenience, should not be used for sync in real application.
std::this_thread::sleep_for(std::chrono::seconds(3));

// Get the robot state and joint model group info.
auto robot_state = planning_scene_monitor->getStateMonitor()->getCurrentState();
const moveit::core::JointModelGroup* joint_model_group =
robot_state->getJointModelGroup(servo_params.move_group_name);

// Set the command type for servo.
servo.setCommandType(CommandType::TWIST);

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

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

std::chrono::seconds timeout_duration(5);
std::chrono::seconds timeout_duration(4);
std::chrono::seconds time_elapsed(0);
auto start_time = std::chrono::steady_clock::now();

// create command queue to build trajectory message and add current robot state
std::deque<KinematicState> joint_cmd_rolling_window;
KinematicState current_state = servo.getCurrentRobotState();
updateSlidingWindow(current_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());

RCLCPP_INFO_STREAM(demo_node->get_logger(), servo.getStatusMessage());
while (rclcpp::ok())
{
const KinematicState joint_state = servo.getNextJointState(target_twist);
KinematicState joint_state = servo.getNextJointState(robot_state, target_twist);
const StatusCode status = servo.getStatus();

auto current_time = std::chrono::steady_clock::now();
Expand All @@ -106,7 +116,16 @@ int main(int argc, char* argv[])
}
else if (status != StatusCode::INVALID)
{
trajectory_outgoing_cmd_pub->publish(composeTrajectoryMessage(servo_params, joint_state));
updateSlidingWindow(joint_state, joint_cmd_rolling_window, servo_params.max_expected_latency, demo_node->now());
if (const auto msg = composeTrajectoryMessage(servo_params, joint_cmd_rolling_window))
{
trajectory_outgoing_cmd_pub->publish(msg.value());
}
if (!joint_cmd_rolling_window.empty())
{
robot_state->setJointGroupPositions(joint_model_group, joint_cmd_rolling_window.back().positions);
robot_state->setJointGroupVelocities(joint_model_group, joint_cmd_rolling_window.back().velocities);
}
}
rate.sleep();
}
Expand Down
12 changes: 5 additions & 7 deletions moveit_ros/moveit_servo/include/moveit_servo/servo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include <tf2_ros/transform_listener.h>
#include <variant>
#include <rclcpp/logger.hpp>
#include <queue>

namespace moveit_servo
{
Expand All @@ -74,10 +75,11 @@ class Servo

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

/**
* \brief Set the type of incoming servo command.
Expand Down Expand Up @@ -122,7 +124,7 @@ class Servo

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

/**
* \brief Updates data depending on joint model group
*/
void updateJointModelGroup();

/**
* \brief Validate the servo parameters
* @param servo_params The servo parameters
Expand Down
9 changes: 6 additions & 3 deletions moveit_ros/moveit_servo/include/moveit_servo/servo_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,9 @@ class ServoNode
void twistCallback(const geometry_msgs::msg::TwistStamped::ConstSharedPtr& msg);
void poseCallback(const geometry_msgs::msg::PoseStamped::ConstSharedPtr& msg);

std::optional<KinematicState> processJointJogCommand();
std::optional<KinematicState> processTwistCommand();
std::optional<KinematicState> processPoseCommand();
std::optional<KinematicState> processJointJogCommand(const moveit::core::RobotStatePtr& robot_state);
std::optional<KinematicState> processTwistCommand(const moveit::core::RobotStatePtr& robot_state);
std::optional<KinematicState> processPoseCommand(const moveit::core::RobotStatePtr& robot_state);

// Variables

Expand Down Expand Up @@ -132,6 +132,9 @@ class ServoNode

// Threads used by ServoNode
std::thread servo_loop_thread_;

// rolling window of joint commands
std::deque<KinematicState> joint_cmd_rolling_window_;
};

} // namespace moveit_servo
Loading

0 comments on commit 0d2d070

Please sign in to comment.