Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add callback for velocity scaling override + fix params namespace not being set #2021

Merged
merged 1 commit into from
Mar 17, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h
Original file line number Diff line number Diff line change
Expand Up @@ -337,6 +337,8 @@ class ServoCalcs
// dynamic parameters
std::string robot_link_command_frame_;
rcl_interfaces::msg::SetParametersResult robotLinkCommandFrameCallback(const rclcpp::Parameter& parameter);
double override_velocity_scaling_factor_;
rcl_interfaces::msg::SetParametersResult overrideVelocityScalingFactorCallback(const rclcpp::Parameter& parameter);

// Load a smoothing plugin
pluginlib::ClassLoader<online_signal_smoothing::SmoothingBaseClass> smoothing_loader_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ struct ServoParameters
using SharedConstPtr = std::shared_ptr<const ServoParameters>;

// Parameter namespace
const std::string ns;
std::string ns;

// ROS Parameters
// Note that all of these are effectively const because the only way to create one of these
Expand Down
26 changes: 24 additions & 2 deletions moveit_ros/moveit_servo/src/servo_calcs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ ServoCalcs::ServoCalcs(const rclcpp::Node::SharedPtr& node,
, stop_requested_(true)
, paused_(false)
, robot_link_command_frame_(parameters->robot_link_command_frame)
, override_velocity_scaling_factor_(parameters->override_velocity_scaling_factor)
, smoothing_loader_("moveit_core", "online_signal_smoothing::SmoothingBaseClass")
{
// Register callback for changes in robot_link_command_frame
Expand All @@ -90,7 +91,16 @@ ServoCalcs::ServoCalcs(const rclcpp::Node::SharedPtr& node,
});
if (!callback_success)
{
throw std::runtime_error("Failed to register setParameterCallback");
throw std::runtime_error("Failed to register setParameterCallback for robot_link_command_frame");
}

// Register callback for changes in override_velocity_scaling_factor
callback_success = parameters_->registerSetParameterCallback(
parameters->ns + ".override_velocity_scaling_factor",
[this](const rclcpp::Parameter& parameter) { return overrideVelocityScalingFactorCallback(parameter); });
if (!callback_success)
{
throw std::runtime_error("Failed to register setParameterCallback for override_velocity_scaling_factor");
}

// MoveIt Setup
Expand Down Expand Up @@ -517,6 +527,18 @@ rcl_interfaces::msg::SetParametersResult ServoCalcs::robotLinkCommandFrameCallba
return result;
};

rcl_interfaces::msg::SetParametersResult
ServoCalcs::overrideVelocityScalingFactorCallback(const rclcpp::Parameter& parameter)
{
const std::lock_guard<std::mutex> lock(main_loop_mutex_);
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
override_velocity_scaling_factor_ = parameter.as_double();
RCLCPP_INFO_STREAM(LOGGER, "override_velocity_scaling_factor changed to: "
<< std::to_string(override_velocity_scaling_factor_));
return result;
};

// Perform the servoing calculations
bool ServoCalcs::cartesianServoCalcs(geometry_msgs::msg::TwistStamped& cmd,
trajectory_msgs::msg::JointTrajectory& joint_trajectory)
Expand Down Expand Up @@ -705,7 +727,7 @@ bool ServoCalcs::internalServoUpdate(Eigen::ArrayXd& delta_theta,

// Enforce SRDF velocity limits
enforceVelocityLimits(joint_model_group_, parameters_->publish_period, internal_joint_state_,
parameters_->override_velocity_scaling_factor);
override_velocity_scaling_factor_);

// Enforce SRDF position limits, might halt if needed, set prev_vel to 0
const auto joints_to_halt = enforcePositionLimits(internal_joint_state_);
Expand Down
2 changes: 2 additions & 0 deletions moveit_ros/moveit_servo/src/servo_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ void ServoParameters::declare(const std::string& ns,
using rclcpp::ParameterType::PARAMETER_INTEGER;
using rclcpp::ParameterType::PARAMETER_STRING;
auto parameters = ServoParameters{};
parameters.ns = ns;

// ROS Parameters
node_parameters->declare_parameter(
Expand Down Expand Up @@ -265,6 +266,7 @@ ServoParameters ServoParameters::get(const std::string& ns,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr& node_parameters)
{
auto parameters = ServoParameters{};
parameters.ns = ns;

// ROS Parameters
parameters.use_gazebo = node_parameters->get_parameter(ns + ".use_gazebo").as_bool();
Expand Down