Skip to content

Commit 8cbdd70

Browse files
authored
Update CI configration to supprot galactic and rolling (#142)
* Make binary build really a build based on released binaries only. * Add binary builds for galactic and rolling. * Base coverage build on rolling. * Add source builds for all distros and correct the branch names there. * Unify files for better maintability. * Correct names and add semi-binary build. * Add CI description into README.md * Delete ci-ursim.yml * Update CI with non-released packages setup for each distro. * Correct spelling. * Update Universal_Robots_ROS2_Driver-not-released.rolling.repos * Add ccache to binary build. * Add ccache into semi-binary build. * Separate CI configuraitons. * Update ci-build-binary-foxy.yml * Update ci-build-binary-galactic.yml * Update ci-build-binary-rolling.yml * Update ci-build-binary-foxy.yml * Update ci-build-binary-galactic.yml * Remove foxy builds from main CI workflows. * Remove deprecated code. * Correct compilation on rolling.
1 parent 2657e27 commit 8cbdd70

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

ur_controllers/include/ur_controllers/scaled_joint_trajectory_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ class ScaledJointTrajectoryController : public joint_trajectory_controller::Join
4545
protected:
4646
struct TimeData
4747
{
48-
TimeData() : time(0.0), period(0.0), uptime(0.0)
48+
TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0)
4949
{
5050
}
5151
rclcpp::Time time;

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ ScaledJointTrajectoryController::on_activate(const rclcpp_lifecycle::State& stat
4141
{
4242
TimeData time_data;
4343
time_data.time = node_->now();
44-
time_data.period = rclcpp::Duration(0, 0);
44+
time_data.period = rclcpp::Duration::from_nanoseconds(0);
4545
time_data.uptime = node_->now();
4646
time_data_.initRT(time_data);
4747
return JointTrajectoryController::on_activate(state);
@@ -55,7 +55,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
5555
RCLCPP_ERROR(get_node()->get_logger(), "Speed scaling interface not found in hardware interface.");
5656
}
5757

58-
if (get_current_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
58+
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
5959
return controller_interface::return_type::OK;
6060
}
6161

@@ -135,7 +135,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
135135
TimeData time_data;
136136
time_data.time = node_->now();
137137
rcl_duration_value_t period = (time_data.time - time_data_.readFromRT()->time).nanoseconds();
138-
time_data.period = rclcpp::Duration(scaling_factor_ * period);
138+
time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * period);
139139
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
140140
rclcpp::Time traj_time = time_data_.readFromRT()->uptime + rclcpp::Duration(period);
141141
time_data_.writeFromNonRT(time_data);

0 commit comments

Comments
 (0)