Skip to content

Commit

Permalink
Asoragna/humble (iRobotEducation#197)
Browse files Browse the repository at this point in the history
* various fixes to support ROS 2 Humble

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* Asoragna/humble fixes (iRobotEducation#196)

* Add Humble CI

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* rename ign_ros2_control package to gazebo_ros2_control

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* use const reference in for loops

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* Humble fix (iRobotEducation#193)

* Fix range redefinition and backward movement

Signed-off-by: Francisco Martín Rico <fmrico@gmail.com>

* Update message names to iRobotEducation/irobot_create_msgs#10

Signed-off-by: Francisco Martín Rico <fmrico@gmail.com>

* Revert safety parameter

Signed-off-by: Francisco Martín Rico <fmrico@gmail.com>

Signed-off-by: Francisco Martín Rico <fmrico@gmail.com>

* fix linter errors

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* add rsl dependency

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* rename dock topic into dock_status

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* fix linking with ignition libraries (iRobotEducation#198)

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* rename ros2_control filename

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* comment ign_ros2_control dependency as it must be built from sources

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

* add link in the readme admonition

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>

Signed-off-by: Alberto Soragna <alberto.soragna@gmail.com>
Signed-off-by: Francisco Martín Rico <fmrico@gmail.com>
Co-authored-by: Francisco Martín Rico <fmrico@gmail.com>
  • Loading branch information
alsora and fmrico authored Jan 19, 2023
1 parent ea16648 commit b7c6901
Show file tree
Hide file tree
Showing 45 changed files with 211 additions and 234 deletions.
23 changes: 5 additions & 18 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,30 +9,17 @@ on:
jobs:
build_and_test:
name: build_and_test
runs-on: ubuntu-20.04
runs-on: ubuntu-22.04
steps:
- name: Set Ignition Version
run: |
echo "IGNITION_VERSION=edifice" >> $GITHUB_ENV
- uses: actions/checkout@v2.3.4
- uses: ros-tooling/setup-ros@0.2.1
- uses: ros-tooling/setup-ros@0.4.1
with:
required-ros-distributions: galactic
- uses: ros-tooling/action-ros-ci@0.2.1
required-ros-distributions: humble
- uses: ros-tooling/action-ros-ci@0.2.7
id: action_ros_ci_step
with:
target-ros2-distro: galactic
target-ros2-distro: humble
import-token: ${{ secrets.REPO_TOKEN }}
package-name:
irobot_create_common_bringup
irobot_create_control
irobot_create_description
irobot_create_nodes
irobot_create_toolbox
irobot_create_gazebo_bringup
irobot_create_gazebo_plugins
irobot_create_gazebo_sim
irobot_create_ignition_bringup
irobot_create_ignition_plugins
irobot_create_ignition_sim
irobot_create_ignition_toolbox
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,15 @@
This is a ROS 2 simulation stack for the [iRobot® Create® 3](https://edu.irobot.com/create3) robot.
Both Ignition Gazebo and Classic Gazebo are supported.

> :warning: **To run with Ignition Gazebo you must first build and install the [`gz_ros2_control`](https://github.com/ros-controls/gz_ros2_control) package master branch from sources!**
Have a look at the [Create® 3 documentation](https://iroboteducation.github.io/create3_docs/) for more details on the ROS 2 interfaces exposed by the robot.

## Prerequisites

Required dependencies:

1. [ROS 2 galactic](https://docs.ros.org/en/galactic/Installation/Ubuntu-Install-Debians.html)
1. [ROS 2 humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html)
2. ROS 2 dev tools:
- [colcon-common-extensions](https://pypi.org/project/colcon-common-extensions/)
- [rosdep](https://pypi.org/project/rosdep/): Used to install dependencies when building from sources
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ robot_state:
stop_status_publish_rate: 62.0
battery_state_publish_rate: 0.1
# Subscription topics
dock_topic: /dock
dock_topic: /dock_status
wheel_vels_topic: /odom
# Stop status position difference tolerance
linear_velocity_tolerance: 0.01
Expand Down
1 change: 1 addition & 0 deletions irobot_create_common/irobot_create_control/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<exec_depend>joint_state_broadcaster</exec_depend>
<exec_depend>ros2launch</exec_depend>
<exec_depend>ros2_controllers</exec_depend>
<exec_depend>rsl</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_cmake_flake8</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@

<xacro:if value="${'$(arg gazebo)' == 'ignition'}">
<gazebo>
<plugin filename="ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters> $(find irobot_create_control)/config/control.yaml </parameters>
</plugin>
</gazebo>
Expand Down Expand Up @@ -252,7 +252,7 @@
<plugin name="dock_status_publisher" filename="libgazebo_ros_create_docking_status.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=dock</remapping>
<remapping>~/out:=dock_status</remapping>
</ros>
<update_rate>1.0</update_rate>
<robot_model_name>${robot_model_name}</robot_model_name>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="ir_emitter" params="name parent:=base_link *origin
gazebo
range
max_range
aperture
update_rate:=1.0
min_range:=${7*cm2m}
Expand Down Expand Up @@ -31,7 +31,7 @@
<xacro:ray_sensor sensor_name="${name}" gazebo="${gazebo}"
update_rate="${update_rate}" visualize="${visualize}"
h_samples="50" h_res="1.0" h_min_angle="-${aperture/2}" h_max_angle="${aperture/2}"
r_min="${min_range}" r_max="${range}" r_res="0.01">
r_min="${min_range}" r_max="${max_range}" r_res="0.01">
<plugin name="dummy" filename="dummyfile"></plugin>
</xacro:ray_sensor>
</gazebo>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
parent="${link_name}"
gazebo="$(arg gazebo)"
aperture="${buoy_lateral_aperture}"
range="1.0"
max_range="1.0"
visualize="$(arg visualize_rays)">
<origin xyz="${buoy_x} 0 ${buoy_z}"
rpy="0 0 ${- buoy_lateral_angle_yaw}"/>
Expand All @@ -56,7 +56,7 @@
parent="${link_name}"
gazebo="$(arg gazebo)"
aperture="${buoy_lateral_aperture}"
range="1.0"
max_range="1.0"
visualize="$(arg visualize_rays)">
<origin xyz="${buoy_x} 0 ${buoy_z}"
rpy="0 0 ${buoy_lateral_angle_yaw}"/>
Expand All @@ -67,7 +67,7 @@
parent="${link_name}"
gazebo="$(arg gazebo)"
aperture="${10*deg2rad}"
range="1.0"
max_range="1.0"
visualize="$(arg visualize_rays)">
<origin xyz="${buoy_x} 0 ${buoy_z}"/>
</xacro:ir_emitter>
Expand All @@ -77,7 +77,7 @@
parent="${link_name}"
gazebo="$(arg gazebo)"
aperture="360"
range="0.6096"
max_range="0.6096"
visualize="$(arg visualize_rays)">
<origin xyz="${buoy_x} 0 ${0.095 - z_offset}"/>
</xacro:ir_emitter>
Expand Down
1 change: 1 addition & 0 deletions irobot_create_common/irobot_create_nodes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ set(dependencies
nav_msgs
rclcpp
rclcpp_action
rclcpp_components
tf2
tf2_geometry_msgs
tf2_ros
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,15 @@
#ifndef IROBOT_CREATE_NODES__MOTION_CONTROL__BEHAVIORS_SCHEDULER_HPP_
#define IROBOT_CREATE_NODES__MOTION_CONTROL__BEHAVIORS_SCHEDULER_HPP_

#include <boost/optional.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <irobot_create_msgs/msg/hazard_detection_vector.hpp>
#include <tf2/LinearMath/Transform.h>

#include <atomic>
#include <functional>
#include <mutex>

#include "boost/optional.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "irobot_create_msgs/msg/hazard_detection_vector.hpp"
#include "tf2/LinearMath/Transform.h"

namespace irobot_create_nodes
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,19 +6,19 @@

#include <stdint.h>

#include <irobot_create_msgs/action/dock_servo.hpp>
#include <irobot_create_msgs/action/undock.hpp>
#include <irobot_create_msgs/msg/dock.hpp>
#include <irobot_create_nodes/motion_control/behaviors_scheduler.hpp>
#include <irobot_create_nodes/motion_control/simple_goal_controller.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <atomic>
#include <memory>

#include "irobot_create_msgs/action/dock.hpp"
#include "irobot_create_msgs/action/undock.hpp"
#include "irobot_create_msgs/msg/dock_status.hpp"
#include "irobot_create_nodes/motion_control/behaviors_scheduler.hpp"
#include "irobot_create_nodes/motion_control/simple_goal_controller.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace irobot_create_nodes
{

Expand All @@ -45,27 +45,27 @@ class DockingBehavior
const tf2::Transform & docked_robot_pose,
const tf2::Transform & dock_pose);

void dock_status_callback(irobot_create_msgs::msg::Dock::ConstSharedPtr msg);
void dock_status_callback(irobot_create_msgs::msg::DockStatus::ConstSharedPtr msg);

void robot_pose_callback(nav_msgs::msg::Odometry::ConstSharedPtr msg);

void dock_pose_callback(nav_msgs::msg::Odometry::ConstSharedPtr msg);

rclcpp_action::GoalResponse handle_dock_servo_goal(
const rclcpp_action::GoalUUID & uuid,
std::shared_ptr<const irobot_create_msgs::action::DockServo::Goal> goal);
std::shared_ptr<const irobot_create_msgs::action::Dock::Goal> goal);

rclcpp_action::CancelResponse handle_dock_servo_cancel(
const std::shared_ptr<
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::DockServo>> goal_handle);
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::Dock>> goal_handle);

void handle_dock_servo_accepted(
const std::shared_ptr<
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::DockServo>> goal_handle);
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::Dock>> goal_handle);

BehaviorsScheduler::optional_output_t execute_dock_servo(
const std::shared_ptr<
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::DockServo>> goal_handle,
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::Dock>> goal_handle,
const RobotState & current_state);

rclcpp_action::GoalResponse handle_undock_goal(
Expand All @@ -85,10 +85,10 @@ class DockingBehavior
rclcpp_action::ServerGoalHandle<irobot_create_msgs::action::Undock>> goal_handle,
const RobotState & current_state);

rclcpp_action::Server<irobot_create_msgs::action::DockServo>::SharedPtr docking_action_server_;
rclcpp_action::Server<irobot_create_msgs::action::Dock>::SharedPtr docking_action_server_;
rclcpp_action::Server<irobot_create_msgs::action::Undock>::SharedPtr undocking_action_server_;

rclcpp::Subscription<irobot_create_msgs::msg::Dock>::SharedPtr dock_status_sub_;
rclcpp::Subscription<irobot_create_msgs::msg::DockStatus>::SharedPtr dock_status_sub_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr robot_pose_sub_;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr dock_pose_sub_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,22 @@
#ifndef IROBOT_CREATE_NODES__MOTION_CONTROL__DRIVE_GOAL_BEHAVIORS_HPP_
#define IROBOT_CREATE_NODES__MOTION_CONTROL__DRIVE_GOAL_BEHAVIORS_HPP_

#include <irobot_create_nodes/motion_control/behaviors_scheduler.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <irobot_create_msgs/action/drive_arc.hpp>
#include <irobot_create_msgs/action/drive_distance.hpp>
#include <irobot_create_msgs/action/navigate_to_position.hpp>
#include <irobot_create_msgs/action/rotate_angle.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>
#include <stdint.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <atomic>
#include <memory>
#include <string>

#include "geometry_msgs/msg/twist.hpp"
#include "irobot_create_nodes/motion_control/behaviors_scheduler.hpp"
#include "irobot_create_msgs/action/drive_arc.hpp"
#include "irobot_create_msgs/action/drive_distance.hpp"
#include "irobot_create_msgs/action/navigate_to_position.hpp"
#include "irobot_create_msgs/action/rotate_angle.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace irobot_create_nodes
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,21 +4,21 @@
#ifndef IROBOT_CREATE_NODES__MOTION_CONTROL__REFLEX_BEHAVIOR_HPP_
#define IROBOT_CREATE_NODES__MOTION_CONTROL__REFLEX_BEHAVIOR_HPP_

#include <irobot_create_msgs/msg/hazard_detection.hpp>
#include <irobot_create_msgs/msg/hazard_detection_vector.hpp>
#include <irobot_create_nodes/motion_control/behaviors_scheduler.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/buffer.h>

#include <atomic>
#include <limits>
#include <map>
#include <memory>
#include <string>
#include <vector>

#include "irobot_create_msgs/msg/hazard_detection.hpp"
#include "irobot_create_msgs/msg/hazard_detection_vector.hpp"
#include "irobot_create_nodes/motion_control/behaviors_scheduler.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2_ros/buffer.h"

namespace irobot_create_nodes
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,18 @@
#ifndef IROBOT_CREATE_NODES__MOTION_CONTROL__SIMPLE_GOAL_CONTROLLER_HPP_
#define IROBOT_CREATE_NODES__MOTION_CONTROL__SIMPLE_GOAL_CONTROLLER_HPP_

#include <angles/angles.h>
#include <boost/optional.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <irobot_create_nodes/motion_control/behaviors_scheduler.hpp>
#include <tf2/utils.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <deque>
#include <functional>
#include <mutex>
#include <vector>

#include "angles/angles.h"
#include "boost/optional.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "irobot_create_nodes/motion_control/behaviors_scheduler.hpp"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace irobot_create_nodes
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,19 +6,19 @@

#include <stdint.h>

#include <irobot_create_msgs/action/wall_follow.hpp>
#include <irobot_create_msgs/msg/hazard_detection_vector.hpp>
#include <irobot_create_msgs/msg/ir_intensity_vector.hpp>
#include <irobot_create_nodes/motion_control/behaviors_scheduler.hpp>
#include <irobot_create_nodes/motion_control/wall_follow_states.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_action/rclcpp_action.hpp>

#include <atomic>
#include <memory>
#include <string>
#include <vector>

#include "irobot_create_msgs/action/wall_follow.hpp"
#include "irobot_create_msgs/msg/hazard_detection_vector.hpp"
#include "irobot_create_msgs/msg/ir_intensity_vector.hpp"
#include "irobot_create_nodes/motion_control/behaviors_scheduler.hpp"
#include "irobot_create_nodes/motion_control/wall_follow_states.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"

namespace irobot_create_nodes
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,16 @@
#ifndef IROBOT_CREATE_NODES__MOTION_CONTROL__WALL_FOLLOW_STATES_HPP_
#define IROBOT_CREATE_NODES__MOTION_CONTROL__WALL_FOLLOW_STATES_HPP_

#include <irobot_create_msgs/action/wall_follow.hpp>
#include <irobot_create_msgs/msg/ir_intensity_vector.hpp>
#include <tf2/utils.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>

#include <atomic>
#include <memory>
#include <string>
#include <vector>

#include "irobot_create_msgs/action/wall_follow.hpp"
#include "irobot_create_msgs/msg/ir_intensity_vector.hpp"
#include "tf2/utils.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"

namespace irobot_create_nodes
{

Expand Down
Loading

0 comments on commit b7c6901

Please sign in to comment.