Skip to content

Commit

Permalink
Drop Foxy support (#756)
Browse files Browse the repository at this point in the history
* update to iron

* remove foxy

* Update lane_follower.py

* remove iron tests

* Update CHANGELOG.rst
  • Loading branch information
ygoumaz authored May 23, 2023
1 parent e762df3 commit 4ba4eb1
Show file tree
Hide file tree
Showing 25 changed files with 40 additions and 169 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ jobs:
fail-fast: false
matrix:
ROS_REPO: [main, testing]
ROS_DISTRO: [foxy, humble, rolling]
ROS_DISTRO: [humble, rolling]
runs-on: ubuntu-latest
env:
AFTER_INIT: ./scripts/ci_after_init.bash ${ROS_DISTRO} ${ROS_REPO}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_develop.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ jobs:
fail-fast: false
matrix:
ROS_REPO: [main, testing]
ROS_DISTRO: [foxy, humble, rolling]
ROS_DISTRO: [humble, rolling]
runs-on: ubuntu-latest
env:
AFTER_INIT: ./scripts/ci_after_init.bash ${ROS_DISTRO} ${ROS_REPO}
Expand Down
4 changes: 2 additions & 2 deletions scripts/ci_after_init.bash
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ if [[ "${ROS_DISTRO}" != "rolling" ]]; then
fi

# TODO: Revert once the https://github.com/ros-planning/navigation2/issues/3033 issue is fixed.
# Fast-DDS is not working properly with the Nav2 package on Humble. Using Cyclone DDS instead.
if [[ "${ROS_DISTRO}" == "humble" ]]; then
# Fast-DDS is not working properly with the Nav2 package on Humble and Iron. Using Cyclone DDS instead.
if [[ "${ROS_DISTRO}" != "rolling" ]]; then
apt install -y ros-${ROS_DISTRO}-rmw-cyclonedds-cpp
fi

Expand Down
2 changes: 1 addition & 1 deletion scripts/ci_before_init_embed.bash
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,6 @@ fi

# TODO: Revert once the https://github.com/ros-planning/navigation2/issues/3033 issue is fixed.
# Fast-DDS is not working properly with the Nav2 package on Humble. Using Cyclone DDS instead.
if [[ "${ROS_DISTRO}" == "humble" ]]; then
if [[ "${ROS_DISTRO}" != "rolling" ]]; then
export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
fi
1 change: 1 addition & 0 deletions webots_ros2/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ Changelog for package webots_ros2

2023.0.4 (2023-05-23)
------------------
* Drop support for Foxy.
* Fixed vertical field of view in static RangeFinder plugin.
* Added support for painted point clouds
* Fixed ability to launch RViz without other tools in e-puck example.
Expand Down
8 changes: 4 additions & 4 deletions webots_ros2_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@ cmake_minimum_required(VERSION 3.5)
project(webots_ros2_control)

# Check which ROS distribution is used, ros2control depends of that
if($ENV{ROS_DISTRO} MATCHES "foxy")
add_compile_definitions(FOXY)
elseif($ENV{ROS_DISTRO} MATCHES "humble")
if($ENV{ROS_DISTRO} MATCHES "humble")
add_compile_definitions(HUMBLE)
elseif($ENV{ROS_DISTRO} MATCHES "iron")
add_compile_definitions(IRON)
elseif($ENV{ROS_DISTRO} MATCHES "rolling")
add_compile_definitions(ROLLING)
endif()
Expand Down Expand Up @@ -36,7 +36,7 @@ find_package(webots_ros2_driver REQUIRED)
add_compile_definitions(HARDWARE_INTERFACE_VERSION_MAJOR=${hardware_interface_VERSION_MAJOR})
add_compile_definitions(HARDWARE_INTERFACE_VERSION_MINOR=${hardware_interface_VERSION_MINOR})

if (MSVC OR MSYS OR MINGW OR WIN32)
if(MSVC OR MSYS OR MINGW OR WIN32)
set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ON)
endif()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,6 @@
#include <thread>
#include <vector>

#if FOXY
#include "hardware_interface/base_interface.hpp"
#include "hardware_interface/types/hardware_interface_status_values.hpp"
#endif

#include "controller_manager/controller_manager.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,6 @@
#include <string>
#include <vector>

#if FOXY
#include "hardware_interface/base_interface.hpp"
#include "hardware_interface/types/hardware_interface_status_values.hpp"
#endif

#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/system_interface.hpp"
Expand Down Expand Up @@ -57,28 +52,17 @@ namespace webots_ros2_control {
Ros2ControlSystem();
void init(webots_ros2_driver::WebotsNode *node, const hardware_interface::HardwareInfo &info) override;

#if FOXY
hardware_interface::return_type configure(const hardware_interface::HardwareInfo &info) override;
hardware_interface::return_type start() override;
hardware_interface::return_type stop() override;
#else
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_init(
const hardware_interface::HardwareInfo &info) override;
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
const rclcpp_lifecycle::State & /*previous_state*/) override;
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & /*previous_state*/) override;
#endif

std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
#if FOXY
hardware_interface::return_type read() override;
hardware_interface::return_type write() override;
#else // HUMBLE, ROLLING
hardware_interface::return_type read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override;
hardware_interface::return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override;
#endif

private:
webots_ros2_driver::WebotsNode *mNode;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,6 @@
#include <string>
#include <vector>

#if FOXY
#include "hardware_interface/base_interface.hpp"
#include "hardware_interface/types/hardware_interface_status_values.hpp"
#endif

#include <webots/supervisor.h>
#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
Expand All @@ -33,18 +28,10 @@
#include "webots_ros2_driver/WebotsNode.hpp"

namespace webots_ros2_control {
#if FOXY
class Ros2ControlSystemInterface : public hardware_interface::BaseInterface<hardware_interface::SystemInterface> {
public:
virtual void init(webots_ros2_driver::WebotsNode *node, const hardware_interface::HardwareInfo &info) = 0;
};
#else
class Ros2ControlSystemInterface : public hardware_interface::SystemInterface {
public:
virtual void init(webots_ros2_driver::WebotsNode *node, const hardware_interface::HardwareInfo &info) = 0;
};
#endif

} // namespace webots_ros2_control

#endif
18 changes: 0 additions & 18 deletions webots_ros2_control/src/Ros2Control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,25 +42,13 @@ namespace webots_ros2_control {
const int nowMs = wb_robot_get_time() * 1000.0;
const int periodMs = nowMs - mLastControlUpdateMs;
if (periodMs >= mControlPeriodMs) {
#if FOXY
mControllerManager->read();
#else
const rclcpp::Duration dt = rclcpp::Duration::from_seconds(mControlPeriodMs / 1000.0);
mControllerManager->read(mNode->get_clock()->now(), dt);
#endif

#if FOXY
mControllerManager->update();
#else
mControllerManager->update(mNode->get_clock()->now(), dt);
mLastControlUpdateMs = nowMs;
#endif

#if FOXY
mControllerManager->write();
#else // HUMBLE, ROLLING
mControllerManager->write(mNode->get_clock()->now(), dt);
#endif
}
}
void Ros2Control::init(webots_ros2_driver::WebotsNode *node, std::unordered_map<std::string, std::string> &) {
Expand Down Expand Up @@ -98,15 +86,9 @@ namespace webots_ros2_control {
mHardwareLoader->createUnmanagedInstance(hardwareType));
#endif
webotsSystem->init(mNode, controlHardware[i]);
#if FOXY
resourceManager->import_component(std::move(webotsSystem));
#else
resourceManager->import_component(std::move(webotsSystem), controlHardware[i]);
#endif

#if HUMBLE || ROLLING
resourceManager->activate_all_components();
#endif
}

// Controller Manager
Expand Down
38 changes: 3 additions & 35 deletions webots_ros2_control/src/Ros2ControlSystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,15 +82,6 @@ namespace webots_ros2_control {
}
}

#if FOXY
hardware_interface::return_type Ros2ControlSystem::configure(const hardware_interface::HardwareInfo &info) {
if (configure_default(info) != hardware_interface::return_type::OK) {
return hardware_interface::return_type::ERROR;
}
status_ = hardware_interface::status::CONFIGURED;
return hardware_interface::return_type::OK;
}
#else
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2ControlSystem::on_init(
const hardware_interface::HardwareInfo &info) {
if (hardware_interface::SystemInterface::on_init(info) !=
Expand All @@ -99,7 +90,6 @@ namespace webots_ros2_control {
}
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
#endif

std::vector<hardware_interface::StateInterface> Ros2ControlSystem::export_state_interfaces() {
std::vector<hardware_interface::StateInterface> interfaces;
Expand Down Expand Up @@ -133,17 +123,6 @@ namespace webots_ros2_control {
return interfaces;
}

#if FOXY
hardware_interface::return_type Ros2ControlSystem::start() {
status_ = hardware_interface::status::STARTED;
return hardware_interface::return_type::OK;
}

hardware_interface::return_type Ros2ControlSystem::stop() {
status_ = hardware_interface::status::STOPPED;
return hardware_interface::return_type::OK;
}
#else
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Ros2ControlSystem::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/) {
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
Expand All @@ -153,14 +132,8 @@ namespace webots_ros2_control {
const rclcpp_lifecycle::State & /*previous_state*/) {
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
#endif

#if FOXY
hardware_interface::return_type Ros2ControlSystem::read()
#else // HUMBLE, ROLLING
hardware_interface::return_type Ros2ControlSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
#endif
{

hardware_interface::return_type Ros2ControlSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) {
static double lastReadTime = 0;

const double deltaTime = wb_robot_get_time() - lastReadTime;
Expand All @@ -181,12 +154,7 @@ namespace webots_ros2_control {
return hardware_interface::return_type::OK;
}

#if FOXY
hardware_interface::return_type Ros2ControlSystem::write()
#else // HUMBLE, ROLLING
hardware_interface::return_type Ros2ControlSystem::write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
#endif
{
hardware_interface::return_type Ros2ControlSystem::write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) {
for (Joint &joint : mJoints) {
if (joint.motor) {
if (joint.controlPosition && !std::isnan(joint.positionCommand))
Expand Down
18 changes: 4 additions & 14 deletions webots_ros2_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,20 +1,15 @@
cmake_minimum_required(VERSION 3.10)
project(webots_ros2_driver)

# Check which ROS distribution is used, ros2control depends of that
if($ENV{ROS_DISTRO} MATCHES "foxy")
add_compile_definitions(FOXY)
endif()

set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_BUILD_WITH_INSTALL_RPATH ON)

# Check which ROS distribution is used, vision_msgs depends of that
if($ENV{ROS_DISTRO} MATCHES "foxy")
add_compile_definitions(FOXY)
elseif($ENV{ROS_DISTRO} MATCHES "humble")
if($ENV{ROS_DISTRO} MATCHES "humble")
add_compile_definitions(HUMBLE)
elseif($ENV{ROS_DISTRO} MATCHES "iron")
add_compile_definitions(IRON)
elseif($ENV{ROS_DISTRO} MATCHES "rolling")
add_compile_definitions(ROLLING)
endif()
Expand All @@ -33,12 +28,7 @@ find_package(vision_msgs REQUIRED)
find_package(webots_ros2_msgs REQUIRED)
find_package(tinyxml2_vendor REQUIRED)
find_package(TinyXML2 REQUIRED)

if($ENV{ROS_DISTRO} MATCHES "foxy")
find_package(PythonLibs 3.8 EXACT REQUIRED)
else()
find_package(PythonLibs 3.10 EXACT REQUIRED)
endif()
find_package(PythonLibs 3.10 EXACT REQUIRED)

add_custom_target(compile-lib-controller ALL
COMMAND ${CMAKE_COMMAND} -E env "WEBOTS_HOME=${CMAKE_CURRENT_SOURCE_DIR}/webots" make release -f Makefile > /dev/null 2>&1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,16 +22,11 @@
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/quaternion.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#if defined(HUMBLE) || defined(ROLLING)
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#else
// Deprecated in Humble and Rolling
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#endif
#include <sensor_msgs/image_encodings.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <std_msgs/msg/color_rgba.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <vision_msgs/msg/detection2_d.hpp>
#include <vision_msgs/msg/detection2_d_array.hpp>
#include <vision_msgs/msg/object_hypothesis_with_pose.hpp>
Expand Down
4 changes: 0 additions & 4 deletions webots_ros2_driver/src/Driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,7 @@ int main(int argc, char **argv) {
webots_ros2_driver::WebotsNode::handleSignals();

rclcpp::InitOptions options{};
#if FOXY
options.shutdown_on_sigint = false;
#else
options.shutdown_on_signal = false;
#endif
rclcpp::init(argc, argv, options);

std::string robotName(wb_robot_get_name());
Expand Down
10 changes: 0 additions & 10 deletions webots_ros2_driver/src/plugins/static/Ros2Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,13 +153,8 @@ namespace webots_ros2_driver {
vision_msgs::msg::ObjectHypothesisWithPose hypothesis;
hypothesis.pose.pose = pose.pose;
detection.results.push_back(hypothesis);
#if FOXY
detection.bbox.center.x = objects[i].position_on_image[0];
detection.bbox.center.y = objects[i].position_on_image[1];
#else
detection.bbox.center.position.x = objects[i].position_on_image[0];
detection.bbox.center.position.y = objects[i].position_on_image[1];
#endif
detection.bbox.size_x = objects[i].size_on_image[0];
detection.bbox.size_y = objects[i].size_on_image[1];
mRecognitionMessage.detections.push_back(detection);
Expand All @@ -169,13 +164,8 @@ namespace webots_ros2_driver {
recognitionWebotsObject.id = objects[i].id;
recognitionWebotsObject.model = std::string(objects[i].model);
recognitionWebotsObject.pose = pose;
#if FOXY
recognitionWebotsObject.bbox.center.x = objects[i].position_on_image[0];
recognitionWebotsObject.bbox.center.y = objects[i].position_on_image[1];
#else
recognitionWebotsObject.bbox.center.position.x = objects[i].position_on_image[0];
recognitionWebotsObject.bbox.center.position.y = objects[i].position_on_image[1];
#endif
recognitionWebotsObject.bbox.size_x = objects[i].size_on_image[0];
recognitionWebotsObject.bbox.size_y = objects[i].size_on_image[1];
for (size_t j = 0; j < objects[i].number_of_colors; j++) {
Expand Down
5 changes: 2 additions & 3 deletions webots_ros2_epuck/launch/robot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,10 +45,9 @@ def get_ros2_nodes(*args):
# ROS control spawners
controller_manager_timeout = ['--controller-manager-timeout', '50']
controller_manager_prefix = 'python.exe' if os.name == 'nt' else ''
use_deprecated_spawner_py = 'ROS_DISTRO' in os.environ and os.environ['ROS_DISTRO'] == 'foxy'
diffdrive_controller_spawner = Node(
package='controller_manager',
executable='spawner' if not use_deprecated_spawner_py else 'spawner.py',
executable='spawner',
output='screen',
prefix=controller_manager_prefix,
arguments=['diffdrive_controller'] + controller_manager_timeout,
Expand All @@ -58,7 +57,7 @@ def get_ros2_nodes(*args):
)
joint_state_broadcaster_spawner = Node(
package='controller_manager',
executable='spawner' if not use_deprecated_spawner_py else 'spawner.py',
executable='spawner',
output='screen',
prefix=controller_manager_prefix,
arguments=['joint_state_broadcaster'] + controller_manager_timeout,
Expand Down
Loading

0 comments on commit 4ba4eb1

Please sign in to comment.