|
17 | 17 | #include <stddef.h> |
18 | 18 | #include <chrono> |
19 | 19 | #include <functional> |
| 20 | +#include <iostream> |
20 | 21 | #include <memory> |
21 | 22 | #include <ostream> |
22 | 23 | #include <ratio> |
@@ -114,12 +115,20 @@ JointTrajectoryController::state_interface_configuration() const |
114 | 115 | conf.names.push_back(joint_name + "/" + interface_type); |
115 | 116 | } |
116 | 117 | } |
| 118 | + conf.names.push_back(params_.speed_scaling_interface_name); |
117 | 119 | return conf; |
118 | 120 | } |
119 | 121 |
|
120 | 122 | controller_interface::return_type JointTrajectoryController::update( |
121 | 123 | const rclcpp::Time & time, const rclcpp::Duration & period) |
122 | 124 | { |
| 125 | + if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name) { |
| 126 | + scaling_factor_ = state_interfaces_.back().get_value(); |
| 127 | + } else { |
| 128 | + RCLCPP_ERROR(get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.", |
| 129 | + params_.speed_scaling_interface_name.c_str()); |
| 130 | + } |
| 131 | + |
123 | 132 | if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) |
124 | 133 | { |
125 | 134 | return controller_interface::return_type::OK; |
@@ -189,25 +198,34 @@ controller_interface::return_type JointTrajectoryController::update( |
189 | 198 | // currently carrying out a trajectory |
190 | 199 | if (has_active_trajectory()) |
191 | 200 | { |
| 201 | + // Adjust time with scaling factor |
| 202 | + TimeData time_data; |
| 203 | + time_data.time = time; |
| 204 | + rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds(); |
| 205 | + time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * t_period); |
| 206 | + time_data.uptime = time_data_.readFromRT()->uptime + time_data.period; |
| 207 | + rclcpp::Time traj_time = time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period); |
| 208 | + time_data_.writeFromNonRT(time_data); |
| 209 | + |
192 | 210 | bool first_sample = false; |
193 | 211 | // if sampling the first time, set the point before you sample |
194 | 212 | if (!traj_external_point_ptr_->is_sampled_already()) |
195 | 213 | { |
196 | 214 | first_sample = true; |
197 | 215 | if (params_.open_loop_control) |
198 | 216 | { |
199 | | - traj_external_point_ptr_->set_point_before_trajectory_msg(time, last_commanded_state_); |
| 217 | + traj_external_point_ptr_->set_point_before_trajectory_msg(traj_time, last_commanded_state_); |
200 | 218 | } |
201 | 219 | else |
202 | 220 | { |
203 | | - traj_external_point_ptr_->set_point_before_trajectory_msg(time, state_current_); |
| 221 | + traj_external_point_ptr_->set_point_before_trajectory_msg(traj_time, state_current_); |
204 | 222 | } |
205 | 223 | } |
206 | 224 |
|
207 | 225 | // find segment for current timestamp |
208 | 226 | TrajectoryPointConstIter start_segment_itr, end_segment_itr; |
209 | 227 | const bool valid_point = traj_external_point_ptr_->sample( |
210 | | - time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); |
| 228 | + traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); |
211 | 229 |
|
212 | 230 | if (valid_point) |
213 | 231 | { |
@@ -934,6 +952,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( |
934 | 952 | controller_interface::CallbackReturn JointTrajectoryController::on_activate( |
935 | 953 | const rclcpp_lifecycle::State &) |
936 | 954 | { |
| 955 | + // Setup time_data buffer used for scaling |
| 956 | + TimeData time_data; |
| 957 | + time_data.time = get_node()->now(); |
| 958 | + time_data.period = rclcpp::Duration::from_nanoseconds(0); |
| 959 | + time_data.uptime = get_node()->now(); |
| 960 | + time_data_.initRT(time_data); |
| 961 | + |
937 | 962 | // order all joints in the storage |
938 | 963 | for (const auto & interface : params_.command_interfaces) |
939 | 964 | { |
|
0 commit comments