@@ -113,6 +113,10 @@ JointTrajectoryController::command_interface_configuration() const
113113 conf.names .push_back (joint_name + " /" + interface_type);
114114 }
115115 }
116+ if (!params_.speed_scaling .command_interface .empty ())
117+ {
118+ conf.names .push_back (params_.speed_scaling .command_interface );
119+ }
116120 return conf;
117121}
118122
@@ -129,12 +133,30 @@ JointTrajectoryController::state_interface_configuration() const
129133 conf.names .push_back (joint_name + " /" + interface_type);
130134 }
131135 }
136+ if (!params_.speed_scaling .state_interface .empty ())
137+ {
138+ conf.names .push_back (params_.speed_scaling .state_interface );
139+ }
132140 return conf;
133141}
134142
135143controller_interface::return_type JointTrajectoryController::update (
136144 const rclcpp::Time & time, const rclcpp::Duration & period)
137145{
146+ if (scaling_state_interface_.has_value ())
147+ {
148+ scaling_factor_ = scaling_state_interface_->get ().get_value ();
149+ }
150+
151+ if (scaling_command_interface_.has_value ())
152+ {
153+ if (!scaling_command_interface_->get ().set_value (scaling_factor_cmd_.load ()))
154+ {
155+ RCLCPP_ERROR (
156+ get_node ()->get_logger (), " Could not set speed scaling factor through command interfaces." );
157+ }
158+ }
159+
138160 auto logger = this ->get_node ()->get_logger ();
139161 // update dynamic parameters
140162 if (param_listener_->is_old (params_))
@@ -197,18 +219,21 @@ controller_interface::return_type JointTrajectoryController::update(
197219 }
198220 else
199221 {
200- traj_time_ += period;
222+ traj_time_ += period * scaling_factor_. load () ;
201223 }
202224
203225 // Sample expected state from the trajectory
204226 current_trajectory_->sample (
205227 traj_time_, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
228+ state_desired_.time_from_start = traj_time_ - current_trajectory_->time_from_start ();
206229
207230 // Sample setpoint for next control cycle
208231 const bool valid_point = current_trajectory_->sample (
209232 traj_time_ + update_period_, interpolation_method_, command_next_, start_segment_itr,
210233 end_segment_itr, false );
211234
235+ state_current_.time_from_start = time - current_trajectory_->time_from_start ();
236+
212237 if (valid_point)
213238 {
214239 const rclcpp::Time traj_start = current_trajectory_->time_from_start ();
@@ -937,10 +962,47 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
937962 resize_joint_trajectory_point (
938963 last_commanded_state_, dof_, std::numeric_limits<double >::quiet_NaN ());
939964
965+ // create services
940966 query_state_srv_ = get_node ()->create_service <control_msgs::srv::QueryTrajectoryState>(
941967 std::string (get_node ()->get_name ()) + " /query_state" ,
942968 std::bind (&JointTrajectoryController::query_state_service, this , _1, _2));
943969
970+ if (
971+ !has_velocity_command_interface_ && !has_acceleration_command_interface_ &&
972+ !has_effort_command_interface_)
973+ {
974+ auto qos = rclcpp::SystemDefaultsQoS ();
975+ qos.transient_local ();
976+ scaling_factor_sub_ = get_node ()->create_subscription <SpeedScalingMsg>(
977+ " ~/speed_scaling_input" , qos,
978+ [&](const SpeedScalingMsg & msg) { set_scaling_factor (msg.factor ); });
979+ RCLCPP_INFO (
980+ logger, " Setting initial scaling factor to %2f" ,
981+ params_.speed_scaling .initial_scaling_factor );
982+ scaling_factor_ = params_.speed_scaling .initial_scaling_factor ;
983+ }
984+ else
985+ {
986+ RCLCPP_WARN_EXPRESSION (
987+ logger, params_.speed_scaling .initial_scaling_factor != 1.0 ,
988+ " Speed scaling is currently only supported for position interfaces. If you want to make use "
989+ " of speed scaling, please only use a position interface when configuring this controller." );
990+ scaling_factor_ = 1.0 ;
991+ }
992+ if (!params_.speed_scaling .state_interface .empty ())
993+ {
994+ RCLCPP_INFO (
995+ logger, " Using scaling state from the hardware from interface %s." ,
996+ params_.speed_scaling .state_interface .c_str ());
997+ }
998+ else
999+ {
1000+ RCLCPP_INFO (
1001+ get_node ()->get_logger (),
1002+ " No scaling interface set. This controller will not read speed scaling from the hardware." );
1003+ }
1004+ scaling_factor_cmd_.store (scaling_factor_.load ());
1005+
9441006 if (get_update_rate () == 0 )
9451007 {
9461008 throw std::runtime_error (" Controller's update rate is set to 0. This should not happen!" );
@@ -965,6 +1027,42 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
9651027 // parse remaining parameters
9661028 default_tolerances_ = get_segment_tolerances (logger, params_);
9671029
1030+ // Set scaling interfaces
1031+ if (!params_.speed_scaling .state_interface .empty ())
1032+ {
1033+ auto it = std::find_if (
1034+ state_interfaces_.begin (), state_interfaces_.end (), [&](auto & interface)
1035+ { return (interface.get_name () == params_.speed_scaling .state_interface ); });
1036+ if (it != state_interfaces_.end ())
1037+ {
1038+ scaling_state_interface_ = *it;
1039+ }
1040+ else
1041+ {
1042+ RCLCPP_ERROR (
1043+ logger, " Did not find speed scaling interface '%s' in state interfaces." ,
1044+ params_.speed_scaling .state_interface .c_str ());
1045+ return CallbackReturn::ERROR;
1046+ }
1047+ }
1048+ if (!params_.speed_scaling .command_interface .empty ())
1049+ {
1050+ auto it = std::find_if (
1051+ command_interfaces_.begin (), command_interfaces_.end (), [&](auto & interface)
1052+ { return (interface.get_name () == params_.speed_scaling .command_interface ); });
1053+ if (it != command_interfaces_.end ())
1054+ {
1055+ scaling_command_interface_ = *it;
1056+ }
1057+ else
1058+ {
1059+ RCLCPP_ERROR (
1060+ logger, " Did not find speed scaling interface '%s' in command interfaces." ,
1061+ params_.speed_scaling .command_interface .c_str ());
1062+ return CallbackReturn::ERROR;
1063+ }
1064+ }
1065+
9681066 // order all joints in the storage
9691067 for (const auto & interface : params_.command_interfaces )
9701068 {
@@ -1159,6 +1257,7 @@ void JointTrajectoryController::publish_state(
11591257 {
11601258 state_publisher_->msg_ .output = command_current_;
11611259 }
1260+ state_publisher_->msg_ .speed_scaling_factor = scaling_factor_;
11621261
11631262 state_publisher_->unlockAndPublish ();
11641263 }
@@ -1653,6 +1752,40 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
16531752 }
16541753}
16551754
1755+ bool JointTrajectoryController::set_scaling_factor (double scaling_factor)
1756+ {
1757+ if (scaling_factor < 0 )
1758+ {
1759+ RCLCPP_WARN (
1760+ get_node ()->get_logger (),
1761+ " Scaling factor has to be greater or equal to 0.0 - Ignoring input!" );
1762+ return false ;
1763+ }
1764+
1765+ if (scaling_factor != scaling_factor_.load ())
1766+ {
1767+ RCLCPP_INFO (
1768+ get_node ()->get_logger ().get_child (" speed_scaling" ), " New scaling factor will be %f" ,
1769+ scaling_factor);
1770+ }
1771+ scaling_factor_.store (scaling_factor);
1772+ if (
1773+ params_.speed_scaling .command_interface .empty () &&
1774+ !params_.speed_scaling .state_interface .empty ())
1775+ {
1776+ RCLCPP_WARN_ONCE (
1777+ get_node ()->get_logger (),
1778+ " Setting the scaling factor while only one-way communication with the hardware is setup. "
1779+ " This will likely get overwritten by the hardware again. If available, please also setup "
1780+ " the speed_scaling_command_interface_name" );
1781+ }
1782+ else
1783+ {
1784+ scaling_factor_cmd_.store (scaling_factor);
1785+ }
1786+ return true ;
1787+ }
1788+
16561789bool JointTrajectoryController::has_active_trajectory () const
16571790{
16581791 return current_trajectory_ != nullptr && current_trajectory_->has_trajectory_msg ();
0 commit comments