Skip to content

SJTC: Update to latest upstream JTC API #1351

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

Merged
merged 1 commit into from
May 6, 2025
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
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,8 @@

#include <optional>
#include <memory>
#include "angles/angles.h"
#include <vector>
#include "joint_trajectory_controller/joint_trajectory_controller.hpp"
#include "joint_trajectory_controller/trajectory.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
Expand All @@ -63,26 +62,35 @@

CallbackReturn on_init() override;

protected:
struct TimeData
{
TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0)
{
}
rclcpp::Time time;
rclcpp::Duration period;
rclcpp::Time uptime;
};

private:
double scaling_factor_{ 1.0 };
realtime_tools::RealtimeBuffer<TimeData> time_data_;
std::atomic<double> scaling_factor_{ 1.0 };

std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>> scaling_state_interface_ =
std::nullopt;

std::shared_ptr<scaled_joint_trajectory_controller::ParamListener> scaled_param_listener_;
scaled_joint_trajectory_controller::Params scaled_params_;

// Private methods copied from Upstream JTC
void update_pids();

/**
* @brief Assigns the values from a trajectory point interface to a joint interface.
*
* @tparam T The type of the joint interface.
* @param[out] joint_interface The reference_wrapper to assign the values to
* @param[in] trajectory_point_interface Containing the values to assign.
* @todo: Use auto in parameter declaration with c++20
*/
template <typename T>
bool assign_interface_from_point(const T& joint_interface, const std::vector<double>& trajectory_point_interface)

Check warning on line 86 in ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

View check run for this annotation

Codecov / codecov/patch

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp#L86

Added line #L86 was not covered by tests
{
bool success = true;

Check warning on line 88 in ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

View check run for this annotation

Codecov / codecov/patch

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp#L88

Added line #L88 was not covered by tests
for (size_t index = 0; index < num_cmd_joints_; ++index) {
success &= joint_interface[index].get().set_value(trajectory_point_interface[map_cmd_to_joints_[index]]);

Check warning on line 90 in ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

View check run for this annotation

Codecov / codecov/patch

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp#L90

Added line #L90 was not covered by tests
}
return success;

Check warning on line 92 in ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

View check run for this annotation

Codecov / codecov/patch

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp#L92

Added line #L92 was not covered by tests
}
};
} // namespace ur_controllers

Expand Down
Loading
Loading