Skip to content

Commit

Permalink
fix build
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Soragna <[email protected]>
  • Loading branch information
alsora committed Jun 15, 2024
1 parent 9cd1497 commit 515804e
Show file tree
Hide file tree
Showing 21 changed files with 70 additions and 84 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@

<xacro:if value="${'$(arg gazebo)' == 'ignition'}">
<gazebo>
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<plugin filename="libgz_ros2_control-system.so" name="gz_ros2_control::IgnitionROS2ControlPlugin">
<parameters>$(find irobot_create_control)/config/control.yaml</parameters>
<ros>
<remapping>~/odom:=odom</remapping>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@
<xacro:if value="${gazebo == 'ignition'}">
<ros2_control name="${wheel_link_name}_controller" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="${wheel_joint_name}">
<state_interface name="velocity" />
Expand Down
4 changes: 2 additions & 2 deletions irobot_create_common/irobot_create_toolbox/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,13 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(ignition-math6 REQUIRED)
find_package(gz-math7 REQUIRED)
find_package(rclcpp REQUIRED)

#### Libraries

set(dependencies
ignition-math6
gz-math7
rclcpp
)

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

#include "ignition/math/Vector2.hh"
#include "gz/math/Vector2.hh"

namespace irobot_create_toolbox
{
Expand All @@ -16,9 +16,9 @@ struct PolarCoordinate
double azimuth;
};

PolarCoordinate toPolar(const ignition::math::Vector2d & cartesian);
PolarCoordinate toPolar(const gz::math::Vector2d & cartesian);

ignition::math::Vector2d fromPolar(const PolarCoordinate & polar);
gz::math::Vector2d fromPolar(const PolarCoordinate & polar);

} // namespace irobot_create_toolbox

Expand Down
1 change: 0 additions & 1 deletion irobot_create_common/irobot_create_toolbox/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>ignition-math6</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_cmake_cppcheck</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,20 +3,20 @@

#include <cmath>

#include "ignition/math/Vector2.hh"
#include "gz/math/Vector2.hh"
#include "irobot_create_toolbox/polar_coordinates.hpp"

namespace irobot_create_toolbox
{

PolarCoordinate toPolar(const ignition::math::Vector2d & cartesian)
PolarCoordinate toPolar(const gz::math::Vector2d & cartesian)
{
return PolarCoordinate{cartesian.Length(), atan2(cartesian.Y(), cartesian.X())};
}

ignition::math::Vector2d fromPolar(const PolarCoordinate & polar)
gz::math::Vector2d fromPolar(const PolarCoordinate & polar)
{
ignition::math::Vector2d cartesian{
gz::math::Vector2d cartesian{
polar.radius * cos(polar.azimuth), polar.radius * sin(polar.azimuth)};
return cartesian;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@ endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(ros_ign_interfaces QUIET)
find_package(ros_gz_interfaces QUIET)

if(NOT ros_ign_interfaces_FOUND)
message(WARNING "ros_ign_interfaces not found. Skipping ${PROJECT_NAME} package.")
if(NOT ros_gz_interfaces_FOUND)
message(WARNING "ros_gz_interfaces not found. Skipping ${PROJECT_NAME} package.")
ament_package()
return()
endif()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,11 @@

<!-- 3D scene -->
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>
</gz-gui>

<engine>ogre2</engine>
<scene>scene</scene>
Expand All @@ -15,7 +15,7 @@

<!-- Play / pause / step -->
<plugin filename="WorldControl" name="World control">
<ignition-gui>
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
Expand All @@ -28,7 +28,7 @@
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>
</gz-gui>

<play_pause>true</play_pause>
<step>true</step>
Expand All @@ -37,7 +37,7 @@

<!-- Time / RTF -->
<plugin filename="WorldStats" name="World stats">
<ignition-gui>
<gz-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
Expand All @@ -50,7 +50,7 @@
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>
</gz-gui>

<sim_time>true</sim_time>
<real_time>true</real_time>
Expand All @@ -60,7 +60,7 @@

<!-- Translate / rotate -->
<plugin filename="TransformControl" name="Transform control">
<ignition-gui>
<gz-gui>
<title>Transform control</title>
<anchors target="3D View">
<line own="left" target="left"/>
Expand All @@ -72,12 +72,12 @@
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#03a9f4</property>
</ignition-gui>
</gz-gui>
</plugin>

<!-- Insert simple shapes -->
<plugin filename="Shapes" name="Shapes">
<ignition-gui>
<gz-gui>
<anchors target="Transform control">
<line own="left" target="right"/>
<line own="top" target="top"/>
Expand All @@ -88,25 +88,25 @@
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#03a9f4</property>
</ignition-gui>
</gz-gui>
</plugin>

<!-- HMI -->
<plugin filename="Create3Hmi" name="Create3Hmi">
<ignition-gui>
<gz-gui>
<property type="bool" key="showTitleBar">true</property>
<property type="string" key="state">docked</property>
<property type="double" key="height">200</property>
<property key="resizable" type="bool">true</property>
</ignition-gui>
</gz-gui>
</plugin>

<!-- Teleop -->
<plugin filename="Teleop">
<topic>/cmd_vel</topic>
<ignition-gui>
<gz-gui>
<property type="bool" key="showTitleBar">true</property>
<property type="string" key="state">docked</property>
<property key="resizable" type="bool">true</property>
</ignition-gui>
</gz-gui>
</plugin>
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
ARGUMENTS = [
DeclareLaunchArgument('bridge', default_value='true',
choices=['true', 'false'],
description='Use ros_ign_bridge'),
description='Use ros_gz_bridge'),
DeclareLaunchArgument('use_sim_time', default_value='true',
choices=['true', 'false'],
description='use_sim_time'),
Expand Down Expand Up @@ -47,7 +47,7 @@ def generate_launch_description():
'irobot_create_ignition_bringup')

# Paths
ros_ign_bridge_launch = PathJoinSubstitution(
ros_gz_bridge_launch = PathJoinSubstitution(
[pkg_irobot_create_ignition_bringup, 'launch', 'create3_ros_ignition_bridge.launch.py'])
create3_nodes_launch = PathJoinSubstitution(
[pkg_irobot_create_common_bringup, 'launch', 'create3_nodes.launch.py'])
Expand Down Expand Up @@ -96,7 +96,7 @@ def generate_launch_description():

# Spawn Create 3
Node(
package='ros_ign_gazebo',
package='ros_gz_sim',
executable='create',
arguments=['-name', robot_name,
'-x', x,
Expand All @@ -109,7 +109,7 @@ def generate_launch_description():

# Spawn dock
Node(
package='ros_ign_gazebo',
package='ros_gz_sim',
executable='create',
arguments=['-name', dock_name,
'-x', x_dock,
Expand All @@ -123,7 +123,7 @@ def generate_launch_description():

# ROS Ign Bridge
IncludeLaunchDescription(
PythonLaunchDescriptionSource([ros_ign_bridge_launch]),
PythonLaunchDescriptionSource([ros_gz_bridge_launch]),
launch_arguments=[
('world', LaunchConfiguration('world')),
('robot_name', robot_name),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,8 @@ def generate_launch_description():
'irobot_create_ignition_plugins')
pkg_irobot_create_description = get_package_share_directory(
'irobot_create_description')
pkg_ros_ign_gazebo = get_package_share_directory(
'ros_ign_gazebo')
pkg_ros_gz_sim = get_package_share_directory(
'ros_gz_sim')

# Set Ignition resource path
ign_resource_path = SetEnvironmentVariable(name='IGN_GAZEBO_RESOURCE_PATH',
Expand All @@ -52,7 +52,7 @@ def generate_launch_description():

# Paths
ign_gazebo_launch = PathJoinSubstitution(
[pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py'])
[pkg_ros_gz_sim, 'launch', 'ign_gazebo.launch.py'])

# Ignition gazebo
ignition_gazebo = IncludeLaunchDescription(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>ros_ign_interfaces</depend>
<depend>ros_gz_interfaces</depend>

<!-- Create3 -->
<exec_depend>irobot_create_description</exec_depend>
Expand All @@ -18,9 +18,9 @@
<exec_depend>irobot_create_ignition_plugins</exec_depend>

<!-- ROS IGN -->
<exec_depend>ign_ros2_control</exec_depend>
<exec_depend>ros_ign_gazebo</exec_depend>
<exec_depend>ros_ign_bridge</exec_depend>
<exec_depend>gz_ros2_control</exec_depend>
<exec_depend>ros_gz_sim</exec_depend>
<exec_depend>ros_gz_bridge</exec_depend>

<!-- Messages -->
<exec_depend>std_msgs</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,16 +11,7 @@ find_package(ament_cmake REQUIRED)
set(OpenGL_GL_PREFERENCE LEGACY)

# Find the Ignition gui library
find_package(ignition-common4 QUIET)
find_package(ignition-gazebo6 QUIET)
find_package(ignition-plugin1 QUIET)

if(NOT ignition-gazebo6_FOUND OR NOT ignition-common4_FOUND OR NOT ignition-plugin1_FOUND)
message(WARNING "Ignition not found. Skipping ${PROJECT_NAME} package.")
ament_package()
return()
endif()

find_package(gz-gui8)
add_subdirectory(Create3Hmi)

if(BUILD_TESTING)
Expand Down
Empty file.
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,7 @@ target_link_libraries(
)
ament_target_dependencies(
Create3Hmi
ignition-common4
ignition-gazebo6
ignition-plugin1
gz-gui8
)

install(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,16 @@

#include "Create3Hmi.hh"

#include <ignition/msgs/int32.pb.h>
#include <gz/msgs/int32.pb.h>

#include <iostream>

#include <ignition/plugin/Register.hh>
#include <ignition/gui/Application.hh>
#include <ignition/gui/MainWindow.hh>
#include <gz/plugin/Register.hh>
#include <gz/gui/Application.hh>
#include <gz/gui/MainWindow.hh>


namespace ignition
namespace gz
{

namespace gui
Expand All @@ -23,9 +23,9 @@ namespace gui
Create3Hmi::Create3Hmi()
: Plugin()
{
this->create3_button_pub_ = ignition::transport::Node::Publisher();
this->create3_button_pub_ = gz::transport::Node::Publisher();
this->create3_button_pub_ =
this->node_.Advertise < ignition::msgs::Int32 > (this->create3_button_topic_);
this->node_.Advertise < gz::msgs::Int32 > (this->create3_button_topic_);
}

Create3Hmi::~Create3Hmi()
Expand All @@ -52,12 +52,12 @@ void Create3Hmi::LoadConfig(const tinyxml2::XMLElement * _pluginElem)

void Create3Hmi::OnCreate3Button(const int button)
{
ignition::msgs::Int32 button_msg;
gz::msgs::Int32 button_msg;

button_msg.set_data(button);

if (!this->create3_button_pub_.Publish(button_msg)) {
ignerr << "ignition::msgs::Int32 message couldn't be published at topic: " <<
ignerr << "gz::msgs::Int32 message couldn't be published at topic: " <<
this->create3_button_topic_ << std::endl;
}
}
Expand All @@ -76,9 +76,9 @@ void Create3Hmi::SetNamespace(const QString &_name)
this->create3_button_topic_ << " ' " <<std::endl;

// Update publisher with new topic.
this->create3_button_pub_ = ignition::transport::Node::Publisher();
this->create3_button_pub_ = gz::transport::Node::Publisher();
this->create3_button_pub_ =
this->node_.Advertise< ignition::msgs::Int32 >
this->node_.Advertise< gz::msgs::Int32 >
(this->create3_button_topic_);
if (!this->create3_button_pub_)
{
Expand All @@ -97,9 +97,9 @@ void Create3Hmi::SetNamespace(const QString &_name)

} // namespace gui

} // namespace ignition
} // namespace gz

// Register this plugin
IGNITION_ADD_PLUGIN(
ignition::gui::Create3Hmi,
ignition::gui::Plugin)
GZ_ADD_PLUGIN(
gz::gui::Create3Hmi,
gz::gui::Plugin)
Loading

0 comments on commit 515804e

Please sign in to comment.