Skip to content

Commit

Permalink
Replace std_msgs with example_interfaces
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Apr 30, 2024
1 parent 27af210 commit b4f061d
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 15 deletions.
8 changes: 4 additions & 4 deletions gz_ros2_control_demos/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(control_msgs REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)

install(DIRECTORY
Expand All @@ -39,13 +39,13 @@ ament_target_dependencies(example_position
add_executable(example_velocity examples/example_velocity.cpp)
ament_target_dependencies(example_velocity
rclcpp
std_msgs
example_interfaces
)

add_executable(example_effort examples/example_effort.cpp)
ament_target_dependencies(example_effort
rclcpp
std_msgs
example_interfaces
)

add_executable(example_diff_drive examples/example_diff_drive.cpp)
Expand All @@ -63,7 +63,7 @@ ament_target_dependencies(example_tricycle_drive
add_executable(example_gripper examples/example_gripper.cpp)
ament_target_dependencies(example_gripper
rclcpp
std_msgs
example_interfaces
)

if(BUILD_TESTING)
Expand Down
6 changes: 3 additions & 3 deletions gz_ros2_control_demos/examples/example_effort.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <rclcpp/rclcpp.hpp>

#include <std_msgs/msg/float64_multi_array.hpp>
#include <example_interfaces/msg/float64_multi_array.hpp>

int main(int argc, char * argv[])
{
Expand All @@ -25,12 +25,12 @@ int main(int argc, char * argv[])
std::shared_ptr<rclcpp::Node> node =
std::make_shared<rclcpp::Node>("effort_test_node");

auto publisher = node->create_publisher<std_msgs::msg::Float64MultiArray>(
auto publisher = node->create_publisher<example_interfaces::msg::Float64MultiArray>(
"/effort_controller/commands", 10);

RCLCPP_INFO(node->get_logger(), "node created");

std_msgs::msg::Float64MultiArray commands;
example_interfaces::msg::Float64MultiArray commands;

using namespace std::chrono_literals;

Expand Down
6 changes: 3 additions & 3 deletions gz_ros2_control_demos/examples/example_gripper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

#include "rclcpp/rclcpp.hpp"

#include "std_msgs/msg/float64_multi_array.hpp"
#include "example_interfaces/msg/float64_multi_array.hpp"

std::shared_ptr<rclcpp::Node> node;

Expand All @@ -31,12 +31,12 @@ int main(int argc, char * argv[])

node = std::make_shared<rclcpp::Node>("gripper_test_node");

auto publisher = node->create_publisher<std_msgs::msg::Float64MultiArray>(
auto publisher = node->create_publisher<example_interfaces::msg::Float64MultiArray>(
"/gripper_controller/commands", 10);

RCLCPP_INFO(node->get_logger(), "node created");

std_msgs::msg::Float64MultiArray commands;
example_interfaces::msg::Float64MultiArray commands;

using namespace std::chrono_literals;

Expand Down
6 changes: 3 additions & 3 deletions gz_ros2_control_demos/examples/example_velocity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,20 +16,20 @@

#include <rclcpp/rclcpp.hpp>

#include <std_msgs/msg/float64_multi_array.hpp>
#include <example_interfaces/msg/float64_multi_array.hpp>

int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);

auto node = std::make_shared<rclcpp::Node>("velocity_test_node");

auto publisher = node->create_publisher<std_msgs::msg::Float64MultiArray>(
auto publisher = node->create_publisher<example_interfaces::msg::Float64MultiArray>(
"/velocity_controller/commands", 10);

RCLCPP_INFO(node->get_logger(), "node created");

std_msgs::msg::Float64MultiArray commands;
example_interfaces::msg::Float64MultiArray commands;

using namespace std::chrono_literals;

Expand Down
4 changes: 2 additions & 2 deletions gz_ros2_control_demos/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,15 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>control_msgs</build_depend>
<build_depend>example_interfaces</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>rclcpp</build_depend>
<build_depend>rclcpp_action</build_depend>
<build_depend>std_msgs</build_depend>

<exec_depend>ament_index_python</exec_depend>
<exec_depend>control_msgs</exec_depend>
<exec_depend>effort_controllers</exec_depend>
<exec_depend>example_interfaces</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>hardware_interface</exec_depend>
<exec_depend>gz_ros2_control</exec_depend>
Expand All @@ -42,7 +43,6 @@
<exec_depend condition="$GZ_VERSION == 'garden'">ros_gz_sim</exec_depend>
<exec_depend condition="$GZ_VERSION == 'fortress'">ros_ign_gazebo</exec_depend>
<exec_depend>ros2controlcli</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>velocity_controllers</exec_depend>
<exec_depend>diff_drive_controller</exec_depend>
<exec_depend>tricycle_controller</exec_depend>
Expand Down

0 comments on commit b4f061d

Please sign in to comment.