1616
1717#include < chrono>
1818#include < functional>
19+ #include < iostream>
1920#include < memory>
2021
2122#include < string>
@@ -116,12 +117,24 @@ JointTrajectoryController::state_interface_configuration() const
116117 conf.names .push_back (joint_name + " /" + interface_type);
117118 }
118119 }
120+ conf.names .push_back (params_.speed_scaling_interface_name );
119121 return conf;
120122}
121123
122124controller_interface::return_type JointTrajectoryController::update (
123125 const rclcpp::Time & time, const rclcpp::Duration & period)
124126{
127+ if (state_interfaces_.back ().get_name () == params_.speed_scaling_interface_name )
128+ {
129+ scaling_factor_ = state_interfaces_.back ().get_value ();
130+ }
131+ else
132+ {
133+ RCLCPP_ERROR (
134+ get_node ()->get_logger (), " Speed scaling interface (%s) not found in hardware interface." ,
135+ params_.speed_scaling_interface_name .c_str ());
136+ }
137+
125138 if (get_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
126139 {
127140 return controller_interface::return_type::OK;
@@ -163,6 +176,16 @@ controller_interface::return_type JointTrajectoryController::update(
163176 // currently carrying out a trajectory
164177 if (has_active_trajectory ())
165178 {
179+ // Adjust time with scaling factor
180+ TimeData time_data;
181+ time_data.time = time;
182+ rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT ()->time ).nanoseconds ();
183+ time_data.period = rclcpp::Duration::from_nanoseconds (scaling_factor_ * t_period);
184+ time_data.uptime = time_data_.readFromRT ()->uptime + time_data.period ;
185+ rclcpp::Time traj_time =
186+ time_data_.readFromRT ()->uptime + rclcpp::Duration::from_nanoseconds (t_period);
187+ time_data_.writeFromNonRT (time_data);
188+
166189 bool first_sample = false ;
167190 // if sampling the first time, set the point before you sample
168191 if (!traj_external_point_ptr_->is_sampled_already ())
@@ -171,19 +194,19 @@ controller_interface::return_type JointTrajectoryController::update(
171194 if (params_.open_loop_control )
172195 {
173196 traj_external_point_ptr_->set_point_before_trajectory_msg (
174- time , last_commanded_state_, joints_angle_wraparound_);
197+ traj_time , last_commanded_state_, joints_angle_wraparound_);
175198 }
176199 else
177200 {
178201 traj_external_point_ptr_->set_point_before_trajectory_msg (
179- time , state_current_, joints_angle_wraparound_);
202+ traj_time , state_current_, joints_angle_wraparound_);
180203 }
181204 }
182205
183206 // find segment for current timestamp
184207 TrajectoryPointConstIter start_segment_itr, end_segment_itr;
185208 const bool valid_point = traj_external_point_ptr_->sample (
186- time , interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
209+ traj_time , interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
187210
188211 if (valid_point)
189212 {
@@ -444,7 +467,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
444467 auto interface_has_values = [](const auto & joint_interface)
445468 {
446469 return std::find_if (
447- joint_interface.begin (), joint_interface.end (), [](const auto & interface)
470+ joint_interface.begin (), joint_interface.end (),
471+ [](const auto & interface)
448472 { return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
449473 };
450474
@@ -514,7 +538,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
514538 auto interface_has_values = [](const auto & joint_interface)
515539 {
516540 return std::find_if (
517- joint_interface.begin (), joint_interface.end (), [](const auto & interface)
541+ joint_interface.begin (), joint_interface.end (),
542+ [](const auto & interface)
518543 { return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
519544 };
520545
@@ -892,6 +917,12 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
892917
893918 // parse remaining parameters
894919 default_tolerances_ = get_segment_tolerances (params_);
920+ // Setup time_data buffer used for scaling
921+ TimeData time_data;
922+ time_data.time = get_node ()->now ();
923+ time_data.period = rclcpp::Duration::from_nanoseconds (0 );
924+ time_data.uptime = get_node ()->now ();
925+ time_data_.initRT (time_data);
895926
896927 // order all joints in the storage
897928 for (const auto & interface : params_.command_interfaces )
0 commit comments