Skip to content

Commit

Permalink
Replaced action_tutorials_interfaces by example_interfaces.
Browse files Browse the repository at this point in the history
  • Loading branch information
StefanFabian committed Dec 3, 2024
1 parent e0ef787 commit 4d64100
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 8 deletions.
3 changes: 1 addition & 2 deletions ros_babel_fish/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,6 @@ if (BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
find_package(action_tutorials_interfaces REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(ros_babel_fish_test_msgs REQUIRED)
Expand All @@ -160,7 +159,7 @@ if (BUILD_TESTING)
target_link_libraries(test_service ${PROJECT_NAME})

ament_add_gtest(test_action_client test/action_client.cpp)
ament_target_dependencies(test_action_client action_tutorials_interfaces example_interfaces ros_babel_fish_test_msgs)
ament_target_dependencies(test_action_client example_interfaces ros_babel_fish_test_msgs)
target_link_libraries(test_action_client ${PROJECT_NAME})

ament_add_gtest(test_action_server test/action_server.cpp)
Expand Down
6 changes: 3 additions & 3 deletions ros_babel_fish/examples/action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@ int main( int argc, char **argv )
auto node = rclcpp::Node::make_shared( "action_client" );
std::thread spin_thread( [node]() { rclcpp::spin( node ); } );
BabelFish fish;
auto client = fish.create_action_client( *node, "fibonacci",
"action_tutorials_interfaces/action/Fibonacci" );
auto client =
fish.create_action_client( *node, "fibonacci", "example_interfaces/action/Fibonacci" );

RCLCPP_INFO( node->get_logger(), "Waiting for server to come up." );
if ( !client->wait_for_action_server( 10s ) ) {
Expand All @@ -33,7 +33,7 @@ int main( int argc, char **argv )
nullptr, // We handle the goal response using the future
[]( BabelFishActionClient::GoalHandle::SharedPtr,
const CompoundMessage::ConstSharedPtr msg ) -> void {
const auto &sequence = ( *msg )["partial_sequence"].as<ArrayMessage<int32_t>>();
const auto &sequence = ( *msg )["sequence"].as<ArrayMessage<int32_t>>();
std::cout << "Feedback is an array of length:" << sequence.size() << std::endl;
for ( size_t i = 0; i < sequence.size(); ++i ) {
std::cout << sequence[i];
Expand Down
2 changes: 1 addition & 1 deletion ros_babel_fish/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
<depend>rosidl_runtime_cpp</depend>
<depend>rosidl_typesupport_cpp</depend>
<depend>rosidl_typesupport_introspection_cpp</depend>
<build_depend>action_tutorials_interfaces</build_depend>
<build_depend>example_interfaces</build_depend>
<build_depend>geometry_msgs</build_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_clang_format</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions ros_babel_fish/test/action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include <ros_babel_fish/babel_fish.hpp>

#include <action_msgs/msg/goal_status_array.h>
#include <action_tutorials_interfaces/action/fibonacci.hpp>
#include <example_interfaces/action/fibonacci.hpp>
#include <ros_babel_fish_test_msgs/action/simple_test.hpp>

#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -49,7 +49,7 @@ TEST( ActionClientTest, actionLookup )
EXPECT_NE( ts, nullptr );
EXPECT_TRUE( Equal( type_support->type_support_handle, *ts ) );

type_support = fish.get_action_type_support( "action_tutorials_interfaces/action/Fibonacci" );
type_support = fish.get_action_type_support( "example_interfaces/action/Fibonacci" );
ASSERT_NE( type_support, nullptr );

const auto *ts_map =
Expand Down

0 comments on commit 4d64100

Please sign in to comment.