@@ -163,6 +163,15 @@ controller_interface::return_type JointTrajectoryController::update(
163163 // currently carrying out a trajectory
164164 if (has_active_trajectory ())
165165 {
166+ TimeData time_data;
167+ time_data.time = time;
168+ rcl_duration_value_t t_period = (time_data.time - time_data_.time ).nanoseconds ();
169+ time_data.period = rclcpp::Duration::from_nanoseconds (
170+ static_cast <rcutils_duration_value_t >(scaling_factor_ * static_cast <double >(t_period)));
171+ time_data.uptime = time_data_.uptime + time_data.period ;
172+ rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds (t_period);
173+ time_data_ = time_data;
174+
166175 bool first_sample = false ;
167176 // if sampling the first time, set the point before you sample
168177 if (!traj_external_point_ptr_->is_sampled_already ())
@@ -171,19 +180,19 @@ controller_interface::return_type JointTrajectoryController::update(
171180 if (params_.open_loop_control )
172181 {
173182 traj_external_point_ptr_->set_point_before_trajectory_msg (
174- time , last_commanded_state_, joints_angle_wraparound_);
183+ traj_time , last_commanded_state_, joints_angle_wraparound_);
175184 }
176185 else
177186 {
178187 traj_external_point_ptr_->set_point_before_trajectory_msg (
179- time , state_current_, joints_angle_wraparound_);
188+ traj_time , state_current_, joints_angle_wraparound_);
180189 }
181190 }
182191
183192 // find segment for current timestamp
184193 TrajectoryPointConstIter start_segment_itr, end_segment_itr;
185194 const bool valid_point = traj_external_point_ptr_->sample (
186- time , interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
195+ traj_time , interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
187196
188197 if (valid_point)
189198 {
@@ -195,7 +204,7 @@ controller_interface::return_type JointTrajectoryController::update(
195204 // time_difference is
196205 // - negative until first point is reached
197206 // - counting from zero to time_from_start of next point
198- double time_difference = time .seconds () - segment_time_from_start.seconds ();
207+ const double time_difference = time_data. uptime .seconds () - segment_time_from_start.seconds ();
199208 bool tolerance_violated_while_moving = false ;
200209 bool outside_goal_tolerance = false ;
201210 bool within_goal_time = true ;
@@ -867,6 +876,16 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
867876 std::string (get_node ()->get_name ()) + " /query_state" ,
868877 std::bind (&JointTrajectoryController::query_state_service, this , _1, _2));
869878
879+ if (params_.speed_scaling_topic_name != " " )
880+ {
881+ auto qos = rclcpp::QoS (10 );
882+ qos.transient_local ();
883+
884+ scaling_factor_sub_ = get_node ()->create_subscription <ScalingFactorMsg>(
885+ params_.speed_scaling_topic_name , qos,
886+ // Explicitly allow factors > 1.0 which is really useful for simulation environments
887+ [&](const ScalingFactorMsg & msg) { scaling_factor_ = msg.data / 100.0 ; });
888+ }
870889 return CallbackReturn::SUCCESS;
871890}
872891
@@ -960,6 +979,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
960979 cmd_timeout_ = 0.0 ;
961980 }
962981
982+ // Reset time_data for the trajectory scaling
983+ TimeData time_data;
984+ time_data.time = get_node ()->now ();
985+ time_data.period = rclcpp::Duration::from_nanoseconds (0 );
986+ time_data.uptime = get_node ()->now ();
987+ time_data_ = time_data;
988+
963989 return CallbackReturn::SUCCESS;
964990}
965991
0 commit comments