Skip to content

Commit

Permalink
Merge pull request #198 from firesurfer/jazzy
Browse files Browse the repository at this point in the history
Enable support for Jazzy / Drop support for Foxy and Galactic
  • Loading branch information
stefanscherzinger authored Oct 20, 2024
2 parents 9f7e620 + 32e1b3a commit f53f798
Show file tree
Hide file tree
Showing 35 changed files with 56 additions and 402 deletions.
19 changes: 0 additions & 19 deletions .github/workflows/industrial_ci_galactic_action.yml

This file was deleted.

2 changes: 1 addition & 1 deletion .github/workflows/industrial_ci_humble_action.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,6 @@ jobs:
- {ROS_DISTRO: humble, ROS_REPO: main}
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v1
- uses: actions/checkout@v4
- uses: 'ros-industrial/industrial_ci@master'
env: ${{matrix.env}}
2 changes: 1 addition & 1 deletion .github/workflows/industrial_ci_iron_action.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,6 @@ jobs:
- {ROS_DISTRO: iron, ROS_REPO: main}
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v1
- uses: actions/checkout@v4
- uses: 'ros-industrial/industrial_ci@master'
env: ${{matrix.env}}
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
name: Foxy
name: Jazzy

on: [push, pull_request]
on:
push:
pull_request:
schedule:
# Run every Friday at 6:30 am to detect breaking APIs
- cron: '30 6 * * 5'


jobs:
Expand All @@ -11,9 +16,10 @@ jobs:
fail-fast: false
matrix:
env:
- {ROS_DISTRO: foxy, ROS_REPO: main}
- {ROS_DISTRO: jazzy, ROS_REPO: testing}
- {ROS_DISTRO: jazzy, ROS_REPO: main}
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v1
- uses: actions/checkout@v4
- uses: 'ros-industrial/industrial_ci@master'
env: ${{matrix.env}}
3 changes: 1 addition & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
![build badge](https://github.com/fzi-forschungszentrum-informatik/cartesian_controllers/actions/workflows/industrial_ci_foxy_action.yml/badge.svg)
![build badge](https://github.com/fzi-forschungszentrum-informatik/cartesian_controllers/actions/workflows/industrial_ci_galactic_action.yml/badge.svg)
![build badge](https://github.com/fzi-forschungszentrum-informatik/cartesian_controllers/actions/workflows/industrial_ci_humble_action.yml/badge.svg)
![build badge](https://github.com/fzi-forschungszentrum-informatik/cartesian_controllers/actions/workflows/industrial_ci_iron_action.yml/badge.svg)
![build badge](https://github.com/fzi-forschungszentrum-informatik/cartesian_controllers/actions/workflows/industrial_ci_jazzy_action.yml/badge.svg)
[![License](https://img.shields.io/badge/License-BSD_3--Clause-blue.svg)](https://opensource.org/licenses/BSD-3-Clause)

# Cartesian Controllers
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,12 +75,7 @@ class CartesianComplianceController : public cartesian_motion_controller::Cartes
public:
CartesianComplianceController();

#if defined CARTESIAN_CONTROLLERS_GALACTIC || defined CARTESIAN_CONTROLLERS_HUMBLE || \
defined CARTESIAN_CONTROLLERS_IRON
virtual LifecycleNodeInterface::CallbackReturn on_init() override;
#elif defined CARTESIAN_CONTROLLERS_FOXY
virtual controller_interface::return_type init(const std::string & controller_name) override;
#endif

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state) override;
Expand All @@ -91,13 +86,8 @@ class CartesianComplianceController : public cartesian_motion_controller::Cartes
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state) override;

#if defined CARTESIAN_CONTROLLERS_GALACTIC || defined CARTESIAN_CONTROLLERS_HUMBLE || \
defined CARTESIAN_CONTROLLERS_IRON
controller_interface::return_type update(const rclcpp::Time & time,
const rclcpp::Duration & period) override;
#elif defined CARTESIAN_CONTROLLERS_FOXY
controller_interface::return_type update() override;
#endif

using Base = cartesian_controller_base::CartesianControllerBase;
using MotionBase = cartesian_motion_controller::CartesianMotionController;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,6 @@ CartesianComplianceController::CartesianComplianceController()
{
}

#if defined CARTESIAN_CONTROLLERS_GALACTIC || defined CARTESIAN_CONTROLLERS_HUMBLE || \
defined CARTESIAN_CONTROLLERS_IRON
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
CartesianComplianceController::on_init()
{
Expand All @@ -77,21 +75,6 @@ CartesianComplianceController::on_init()

return TYPE::SUCCESS;
}
#elif defined CARTESIAN_CONTROLLERS_FOXY
controller_interface::return_type CartesianComplianceController::init(
const std::string & controller_name)
{
using TYPE = controller_interface::return_type;
if (MotionBase::init(controller_name) != TYPE::OK || ForceBase::init(controller_name) != TYPE::OK)
{
return TYPE::ERROR;
}

auto_declare<std::string>("compliance_ref_link", "");

return TYPE::OK;
}
#endif

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
CartesianComplianceController::on_configure(const rclcpp_lifecycle::State & previous_state)
Expand Down Expand Up @@ -146,13 +129,8 @@ CartesianComplianceController::on_deactivate(const rclcpp_lifecycle::State & pre
return TYPE::SUCCESS;
}

#if defined CARTESIAN_CONTROLLERS_GALACTIC || defined CARTESIAN_CONTROLLERS_HUMBLE || \
defined CARTESIAN_CONTROLLERS_IRON
controller_interface::return_type CartesianComplianceController::update(
const rclcpp::Time & time, const rclcpp::Duration & period)
#elif defined CARTESIAN_CONTROLLERS_FOXY
controller_interface::return_type CartesianComplianceController::update()
#endif
{
// Synchronize the internal model and the real robot
Base::m_ik_solver->synchronizeJointPositions(Base::m_joint_state_pos_handles);
Expand Down
14 changes: 6 additions & 8 deletions cartesian_controller_base/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,16 +13,14 @@ endif(NOT CMAKE_BUILD_TYPE)

# Use CMake to pass the current ROS_DISTRO via variables into a preprocessor template.
# We then include this file and switch between the different APIs.
if($ENV{ROS_DISTRO} STREQUAL "iron")
set(CARTESIAN_CONTROLLERS_IRON TRUE)
if($ENV{ROS_DISTRO} STREQUAL "jazzy")
set(CARTESIAN_CONTROLLERS_JAZZY TRUE)
elseif($ENV{ROS_DISTRO} STREQUAL "iron")
set(CARTESIAN_CONTROLLERS_IRON TRUE)
elseif($ENV{ROS_DISTRO} STREQUAL "humble")
set(CARTESIAN_CONTROLLERS_HUMBLE TRUE)
elseif($ENV{ROS_DISTRO} STREQUAL "galactic")
set(CARTESIAN_CONTROLLERS_GALACTIC TRUE)
elseif($ENV{ROS_DISTRO} STREQUAL "foxy")
set(CARTESIAN_CONTROLLERS_FOXY TRUE)
set(CARTESIAN_CONTROLLERS_HUMBLE TRUE)
else()
message(WARNING "ROS2 version must be {iron|humble|galactic|foxy}")
message(WARNING "ROS2 version must be {jazzy|iron|humble}")
endif()
configure_file(include/cartesian_controller_base/ROS2VersionConfig.h.in ROS2VersionConfig.h)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,9 @@ class DampedLeastSquaresSolver : public IKSolver
*
* \return True, if everything went well
*/
#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,

bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh, const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits) override;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,12 +103,9 @@ class ForwardDynamicsSolver : public IKSolver
*
* @return True, if everything went well
*/
#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,

bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh, const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits) override;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -147,13 +147,9 @@ class IKSolver
*
* @return True, if everything went well
*/
#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
virtual bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
virtual bool init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits);

virtual bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh, const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits, const KDL::JntArray & lower_pos_limits);

/**
* @brief Update the robot kinematics of the solver
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,12 +87,9 @@ class JacobianTransposeSolver : public IKSolver
*
* \return True, if everything went well
*/
#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> /*nh*/,
#else
bool init(std::shared_ptr<rclcpp::Node> /*nh*/,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,

bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> /*nh*/, const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits) override;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,20 +62,12 @@ class PDController
PDController();
~PDController();

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
void init(const std::string & params, std::shared_ptr<rclcpp_lifecycle::LifecycleNode> handle);
#else
void init(const std::string & params, std::shared_ptr<rclcpp::Node> handle);
#endif

double operator()(const double & error, const rclcpp::Duration & period);

private:
#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> m_handle;
#else
std::shared_ptr<rclcpp::Node> m_handle; ///< handle for dynamic parameter interaction
#endif
std::string m_params; ///< namespace for parameter access

// Gain parameters
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
// Cmake will update these defines depending on our current ROS_DISTRO.
// We use this mechanism to react to API changes in ROS2-control.
//
#cmakedefine CARTESIAN_CONTROLLERS_FOXY
#cmakedefine CARTESIAN_CONTROLLERS_GALACTIC

#cmakedefine CARTESIAN_CONTROLLERS_HUMBLE
#cmakedefine CARTESIAN_CONTROLLERS_IRON
#cmakedefine CARTESIAN_CONTROLLERS_JAZZY
Original file line number Diff line number Diff line change
Expand Up @@ -91,12 +91,9 @@ class SelectivelyDampedLeastSquaresSolver : public IKSolver
*
* \return True, if everything went well
*/
#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,

bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh, const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits) override;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,11 +58,7 @@ class SpatialPDController
public:
SpatialPDController();

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> params);
#else
bool init(std::shared_ptr<rclcpp::Node> params);
#endif

/**
* @brief Call operator for one control cycle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,12 +87,7 @@ class CartesianControllerBase : public controller_interface::ControllerInterface
virtual controller_interface::InterfaceConfiguration state_interface_configuration()
const override;

#if defined CARTESIAN_CONTROLLERS_GALACTIC || defined CARTESIAN_CONTROLLERS_HUMBLE || \
defined CARTESIAN_CONTROLLERS_IRON
virtual LifecycleNodeInterface::CallbackReturn on_init() override;
#elif defined CARTESIAN_CONTROLLERS_FOXY
virtual controller_interface::return_type init(const std::string & controller_name) override;
#endif

rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state) override;
Expand Down
4 changes: 0 additions & 4 deletions cartesian_controller_base/src/DampedLeastSquaresSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,11 +112,7 @@ trajectory_msgs::msg::JointTrajectoryPoint DampedLeastSquaresSolver::getJointCon
return control_cmd;
}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool DampedLeastSquaresSolver::init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool DampedLeastSquaresSolver::init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits)
Expand Down
4 changes: 0 additions & 4 deletions cartesian_controller_base/src/ForwardDynamicsSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,11 +117,7 @@ trajectory_msgs::msg::JointTrajectoryPoint ForwardDynamicsSolver::getJointContro
return control_cmd;
}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool ForwardDynamicsSolver::init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool ForwardDynamicsSolver::init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits)
{
Expand Down
4 changes: 0 additions & 4 deletions cartesian_controller_base/src/IKSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,11 +102,7 @@ void IKSolver::synchronizeJointPositions(
}
}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool IKSolver::init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> /*nh*/,
#else
bool IKSolver::init(std::shared_ptr<rclcpp::Node> /*nh*/,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits)
{
Expand Down
4 changes: 0 additions & 4 deletions cartesian_controller_base/src/JacobianTransposeSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,11 +102,7 @@ trajectory_msgs::msg::JointTrajectoryPoint JacobianTransposeSolver::getJointCont
return control_cmd;
}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool JacobianTransposeSolver::init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool JacobianTransposeSolver::init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain, const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits)
{
Expand Down
4 changes: 0 additions & 4 deletions cartesian_controller_base/src/PDController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,12 +47,8 @@ PDController::PDController() : m_last_p_error(0.0) {}

PDController::~PDController() {}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
void PDController::init(const std::string & params,
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> handle)
#else
void PDController::init(const std::string & params, std::shared_ptr<rclcpp::Node> handle)
#endif
{
m_params = params;
m_handle = std::move(handle);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -136,11 +136,7 @@ trajectory_msgs::msg::JointTrajectoryPoint SelectivelyDampedLeastSquaresSolver::
return control_cmd;
}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool SelectivelyDampedLeastSquaresSolver::init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> nh,
#else
bool SelectivelyDampedLeastSquaresSolver::init(std::shared_ptr<rclcpp::Node> nh,
#endif
const KDL::Chain & chain,
const KDL::JntArray & upper_pos_limits,
const KDL::JntArray & lower_pos_limits)
Expand Down
4 changes: 0 additions & 4 deletions cartesian_controller_base/src/SpatialPDController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,11 +56,7 @@ ctrl::Vector6D SpatialPDController::operator()(const ctrl::Vector6D & error,
return m_cmd;
}

#if defined CARTESIAN_CONTROLLERS_HUMBLE || defined CARTESIAN_CONTROLLERS_IRON
bool SpatialPDController::init(std::shared_ptr<rclcpp_lifecycle::LifecycleNode> handle)
#else
bool SpatialPDController::init(std::shared_ptr<rclcpp::Node> handle)
#endif
{
// Create pd controllers for each Cartesian dimension
for (int i = 0; i < 6; ++i) // 3 transition, 3 rotation
Expand Down
Loading

0 comments on commit f53f798

Please sign in to comment.