├── .gitignore ├── ros_babel_fish_test_msgs ├── msg │ ├── TestSubArray.msg │ ├── TestArray.msg │ └── TestMessage.msg ├── action │ └── SimpleTest.action ├── package.xml ├── CHANGELOG.rst └── CMakeLists.txt ├── ros_babel_fish ├── test │ ├── test_message.test │ ├── test_message_lookup.test │ ├── test_service_lookup.test │ ├── test_message_decoding.test │ ├── test_message_encoding.test │ ├── test_message_extractor.test │ ├── test_action_client.test │ ├── test_service_client.test │ ├── all_tests.test │ ├── service_client_test_services.cpp │ ├── service_client.cpp │ ├── action_client_test_server.cpp │ ├── action_client.cpp │ ├── common.h │ ├── message_extractor.cpp │ └── service_lookup.cpp ├── include │ └── ros_babel_fish │ │ ├── message_types.h │ │ ├── exceptions │ │ ├── babel_fish_exception.h │ │ ├── invalid_location_exception.h │ │ ├── invalid_template_exception.h │ │ └── invalid_message_path_exception.h │ │ ├── generation │ │ ├── message_creation.h │ │ ├── message_template.h │ │ ├── providers │ │ │ ├── integrated_description_provider.h │ │ │ └── message_only_description_provider.h │ │ └── description_provider.h │ │ ├── message_description.h │ │ ├── actionlib │ │ ├── babel_fish_action.h │ │ ├── babel_fish_action_result.h │ │ ├── babel_fish_action_feedback.h │ │ └── babel_fish_action_goal.h │ │ ├── messages │ │ ├── compound_message.h │ │ ├── internal │ │ │ └── value_compatibility.h │ │ └── value_message.h │ │ ├── macros.h │ │ ├── message_extractor.h │ │ ├── babel_fish.h │ │ └── babel_fish_message.h ├── examples │ ├── service_client.cpp │ ├── service_server.cpp │ ├── message_info.cpp │ ├── action_client.cpp │ ├── service_info.cpp │ ├── any_publisher.cpp │ ├── rosbag_frame_ids.cpp │ ├── troll_node.cpp │ └── any_subscriber.cpp ├── package.xml ├── src │ ├── babel_fish_message.cpp │ ├── generation │ │ ├── message_creation.cpp │ │ └── providers │ │ │ └── integrated_description_provider.cpp │ ├── messages │ │ └── value_message.cpp │ ├── babel_fish.cpp │ └── message.cpp ├── CHANGELOG.rst └── CMakeLists.txt ├── .codecov.yml ├── LICENSE ├── .travis.yml └── README.md /.gitignore: -------------------------------------------------------------------------------- 1 | .idea/ 2 | .vscode/ 3 | cmake-build-debug/ 4 | cmake-build-release/ 5 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/msg/TestSubArray.msg: -------------------------------------------------------------------------------- 1 | int32[] ints 2 | string[] strings 3 | time[42] times -------------------------------------------------------------------------------- /ros_babel_fish/test/test_message.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/action/SimpleTest.action: -------------------------------------------------------------------------------- 1 | # goal 2 | int32 goal 3 | --- 4 | # result 5 | int32 result 6 | --- 7 | # feedback 8 | int32 feedback -------------------------------------------------------------------------------- /ros_babel_fish/test/test_message_lookup.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | -------------------------------------------------------------------------------- /ros_babel_fish/test/test_service_lookup.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | -------------------------------------------------------------------------------- /ros_babel_fish/test/test_message_decoding.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | -------------------------------------------------------------------------------- /ros_babel_fish/test/test_message_encoding.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | -------------------------------------------------------------------------------- /ros_babel_fish/test/test_message_extractor.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | -------------------------------------------------------------------------------- /.codecov.yml: -------------------------------------------------------------------------------- 1 | codecov: 2 | require_ci_to_pass: yes 3 | 4 | coverage: 5 | precision: 2 6 | round: down 7 | 8 | ignore: 9 | - "devel" 10 | - "ros_babel_fish/test" 11 | -------------------------------------------------------------------------------- /ros_babel_fish/test/test_action_client.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /ros_babel_fish/test/test_service_client.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/msg/TestArray.msg: -------------------------------------------------------------------------------- 1 | bool[] bools 2 | uint8[] uint8s 3 | uint16[32] uint16s 4 | uint32[] uint32s 5 | uint64[] uint64s 6 | int8[] int8s 7 | int16[] int16s 8 | int32[] int32s 9 | int64[32] int64s#Comment 10 | float32[] float32s 11 | float64[16] float64s 12 | time[] times 13 | duration[12] durations 14 | string[] strings 15 | TestSubArray[10] subarrays_fixed 16 | TestSubArray[] subarrays 17 | 18 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/msg/TestMessage.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | bool b 3 | uint8 ui8 4 | uint16 ui16 5 | uint32 ui32 6 | uint64 ui64 7 | int8 i8 8 | int16 i16 9 | int32 i32 10 | 11 | int64 i64 12 | float32 f32 # Comment 13 | float64 f64#Also a comment but closer 14 | string str## Two comment signs # and a third 15 | time t 16 | duration d 17 | geometry_msgs/Point[] point_arr # more comment 18 | 19 | bool FLAG1 =1 20 | bool FLAG2= 0 21 | bool FLAG3=True 22 | bool FLAG4 = False 23 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/message_types.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MESSAGE_TYPES_H 5 | #define ROS_BABEL_FISH_MESSAGE_TYPES_H 6 | 7 | #include "ros_babel_fish/messages/array_message.h" 8 | #include "ros_babel_fish/messages/compound_message.h" 9 | #include "ros_babel_fish/messages/value_message.h" 10 | 11 | #endif //ROS_BABEL_FISH_MESSAGE_TYPES_H 12 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ros_babel_fish_test_msgs 4 | 0.9.3 5 | Test messages for the ros_babel_fish project tests. 6 | 7 | Stefan Fabian 8 | 9 | MIT 10 | 11 | catkin 12 | 13 | message_generation 14 | message_runtime 15 | actionlib_msgs 16 | std_msgs 17 | geometry_msgs 18 | 19 | -------------------------------------------------------------------------------- /ros_babel_fish/test/all_tests.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/exceptions/babel_fish_exception.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_EXCEPTION_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_EXCEPTION_H 6 | 7 | #include 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | class BabelFishException : public ros::Exception 13 | { 14 | public: 15 | explicit BabelFishException( const std::string &msg ) : ros::Exception( msg ) { } 16 | }; 17 | } // ros_babel_fish 18 | 19 | #endif //ROS_BABEL_FISH_BABEL_FISH_EXCEPTION_H 20 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/exceptions/invalid_location_exception.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_INVALID_LOCATION_EXCEPTION_H 5 | #define ROS_BABEL_FISH_INVALID_LOCATION_EXCEPTION_H 6 | 7 | #include "babel_fish_exception.h" 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | class InvalidLocationException : public BabelFishException 13 | { 14 | public: 15 | explicit InvalidLocationException( const std::string &msg ) : BabelFishException( msg ) { } 16 | }; 17 | } // ros_babel_fish 18 | 19 | #endif // ROS_BABEL_FISH_INVALID_LOCATION_EXCEPTION_H 20 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/exceptions/invalid_template_exception.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_INVALID_TEMPLATE_EXCEPTION_H 5 | #define ROS_BABEL_FISH_INVALID_TEMPLATE_EXCEPTION_H 6 | 7 | #include "babel_fish_exception.h" 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | class InvalidTemplateException : public BabelFishException 13 | { 14 | public: 15 | explicit InvalidTemplateException( const std::string &msg ) : BabelFishException( msg ) { } 16 | }; 17 | } // ros_babel_fish 18 | 19 | #endif // ROS_BABEL_FISH_INVALID_TEMPLATE_EXCEPTION_H 20 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/exceptions/invalid_message_path_exception.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_INVALID_MESSAGE_PATH_EXCEPTION_H 5 | #define ROS_BABEL_FISH_INVALID_MESSAGE_PATH_EXCEPTION_H 6 | 7 | #include "babel_fish_exception.h" 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | class InvalidMessagePathException : public BabelFishException 13 | { 14 | public: 15 | explicit InvalidMessagePathException( const std::string &msg ) : BabelFishException( msg ) { } 16 | }; 17 | } // ros_babel_fish 18 | 19 | #endif // ROS_BABEL_FISH_INVALID_MESSAGE_PATH_EXCEPTION_H 20 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/generation/message_creation.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MESSAGE_CREATION_H 5 | #define ROS_BABEL_FISH_MESSAGE_CREATION_H 6 | 7 | #include "ros_babel_fish/message.h" 8 | #include "message_template.h" 9 | 10 | namespace ros_babel_fish 11 | { 12 | 13 | Message::Ptr createValueMessageFromData( MessageType type, const uint8_t *stream, size_t &bytes_read ); 14 | 15 | Message::Ptr createMessageFromTemplate( const MessageTemplate::ConstPtr &msg_template, const uint8_t *stream, size_t length, 16 | size_t &bytes_read ); 17 | 18 | Message::Ptr createEmptyMessageFromTemplate( const MessageTemplate::ConstPtr &msg_template ); 19 | } // ros_babel_fish 20 | 21 | #endif //ROS_BABEL_FISH_MESSAGE_CREATION_H 22 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/service_client.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | using namespace ros_babel_fish; 9 | 10 | int main( int argc, char **argv ) 11 | { 12 | ros::init( argc, argv, "ros_babel_fish_any_service_client" ); 13 | ros::NodeHandle nh; 14 | 15 | BabelFish fish; 16 | Message::Ptr req = fish.createServiceRequest( "roscpp_tutorials/TwoInts" ); 17 | req->as()["a"] = 314; 18 | (*req)["b"] = 1337; 19 | TranslatedMessage::Ptr res; 20 | std::cout << "Call result: " << fish.callService( "/ros_babel_fish/service", req, res ) << std::endl; 21 | std::cout << "Response:" << std::endl; 22 | std::cout << " sum: " << res->translated_message->as()["sum"].value() << std::endl; 23 | } 24 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/service_server.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | using namespace ros_babel_fish; 9 | 10 | int main( int argc, char **argv ) 11 | { 12 | ros::init( argc, argv, "ros_babel_fish_any_service_server" ); 13 | ros::NodeHandle nh; 14 | 15 | BabelFish fish; 16 | 17 | ros::ServiceServer server = fish.advertiseService( 18 | nh, "roscpp_tutorials/TwoInts", "/ros_babel_fish/service", 19 | []( Message &req, Message &res ) -> bool 20 | { 21 | auto &msg = req.as(); 22 | std::cout << "Received request: " << std::endl; 23 | std::cout << "a: " << msg["a"].value() << std::endl; 24 | std::cout << "b: " << msg["b"].value() << std::endl; 25 | res["sum"] = 42; 26 | return true; 27 | } ); 28 | ros::spin(); 29 | } 30 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2019 Stefan Fabian 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/message_description.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MESSAGE_DESCRIPTION_H 5 | #define ROS_BABEL_FISH_MESSAGE_DESCRIPTION_H 6 | 7 | #include "ros_babel_fish/generation/message_template.h" 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | struct MessageDescription 13 | { 14 | typedef std::shared_ptr Ptr; 15 | typedef std::shared_ptr ConstPtr; 16 | 17 | std::string datatype; 18 | std::string md5; 19 | std::string message_definition; 20 | std::string specification; 21 | 22 | MessageTemplate::ConstPtr message_template; 23 | }; 24 | 25 | struct ServiceDescription 26 | { 27 | typedef std::shared_ptr Ptr; 28 | typedef std::shared_ptr ConstPtr; 29 | 30 | std::string datatype; 31 | std::string md5; 32 | std::string specification; 33 | 34 | MessageDescription::ConstPtr request; 35 | MessageDescription::ConstPtr response; 36 | }; 37 | } // ros_babel_fish 38 | 39 | #endif //ROS_BABEL_FISH_MESSAGE_DESCRIPTION_H 40 | -------------------------------------------------------------------------------- /ros_babel_fish/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ros_babel_fish 4 | 0.9.3 5 | 6 | A runtime message handler for ROS. 7 | Allows subscription, publishing, calling of services and actions with messages known only at runtime. 8 | 9 | 10 | Stefan Fabian 11 | 12 | MIT 13 | 14 | Stefan Fabian --> 15 | 16 | catkin 17 | 18 | libssl-dev 19 | libssl-dev 20 | actionlib 21 | openssl 22 | roscpp 23 | roslib 24 | geometry_msgs 25 | ros_babel_fish_test_msgs 26 | rosapi 27 | roscpp_tutorials 28 | rosgraph_msgs 29 | rostest 30 | std_msgs 31 | std_srvs 32 | visualization_msgs 33 | 34 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package ros_babel_fish_test_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.9.3 (2022-04-20) 6 | ------------------ 7 | 8 | 0.9.2 (2021-12-22) 9 | ------------------ 10 | * Accept True and False as boolean constants (`#4 `_) 11 | * Contributors: Martin Valgur 12 | 13 | 0.9.1 (2020-10-29) 14 | ------------------ 15 | * Added missing build depend for openssl headers to fix build for noetic. 16 | * Contributors: Stefan Fabian 17 | 18 | 0.9.0 (2020-10-28) 19 | ------------------ 20 | * Added install target for service_info. Cleaned up package.xml 21 | * Contributors: Stefan Fabian 22 | 23 | 0.8.0 (2020-03-20) 24 | ------------------ 25 | * Added specialization for action client to allow creating an ActionClient with a BabelFishAction. 26 | * Renamed targets to include ${PROJECT_NAME} prefix to fix `#3 `_. 27 | * Cleanup for initial release. 28 | Added convenience methods. 29 | Added a lot of tests. 30 | * Cleanup for initial release. 31 | Added convenience methods. 32 | Added a lot of tests. 33 | * Contributors: Stefan Fabian 34 | -------------------------------------------------------------------------------- /ros_babel_fish_test_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5.1) 2 | project(ros_babel_fish_test_msgs VERSION 0.9.1) 3 | 4 | find_package(catkin REQUIRED COMPONENTS actionlib_msgs message_generation std_msgs geometry_msgs) 5 | 6 | ################################################ 7 | ## Declare ROS messages, services and actions ## 8 | ################################################ 9 | 10 | ## Generate messages in the 'msg' folder 11 | add_message_files( 12 | FILES 13 | TestArray.msg 14 | TestMessage.msg 15 | TestSubArray.msg 16 | ) 17 | 18 | ## Generate services in the 'srv' folder 19 | # add_service_files( 20 | # FILES 21 | # Service1.srv 22 | # Service2.srv 23 | # ) 24 | 25 | ## Generate actions in the 'action' folder 26 | add_action_files( 27 | DIRECTORY action 28 | FILES 29 | SimpleTest.action 30 | ) 31 | 32 | ## Generate added messages and services with any dependencies listed here 33 | generate_messages( 34 | DEPENDENCIES 35 | actionlib_msgs 36 | std_msgs 37 | geometry_msgs 38 | ) 39 | 40 | ################################### 41 | ## catkin specific configuration ## 42 | ################################### 43 | catkin_package( 44 | CATKIN_DEPENDS message_runtime actionlib_msgs std_msgs geometry_msgs 45 | ) 46 | -------------------------------------------------------------------------------- /ros_babel_fish/test/service_client_test_services.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 04.09.19. 3 | // 4 | 5 | #include 6 | 7 | #include 8 | #include 9 | 10 | using namespace ros_babel_fish; 11 | 12 | bool twoIntServiceCallback( roscpp_tutorials::TwoInts::Request &req, roscpp_tutorials::TwoInts::Response &resp ) 13 | { 14 | resp.sum = req.a + req.b + 42; 15 | return true; 16 | } 17 | 18 | int main( int argc, char **argv ) 19 | { 20 | ros::init( argc, argv, "service_client_test_services" ); 21 | ros::NodeHandle nh; 22 | ros::ServiceServer server1 = nh.advertiseService( "/test_service_client/two_ints", 23 | twoIntServiceCallback ); 24 | 25 | BabelFish fish; 26 | 27 | ros::ServiceServer server2 = fish.advertiseService( 28 | nh, "rosapi/Subscribers", "/test_service_server/subscribers", 29 | []( Message &req, Message &resp ) -> bool 30 | { 31 | resp["subscribers"].as>().push_back( req["topic"].value()); 32 | resp["subscribers"].as>().push_back( "The answer to everything is:" ); 33 | 34 | return true; 35 | } ); 36 | 37 | ros::spin(); 38 | return 0; 39 | } -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/generation/message_template.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MESSAGE_TEMPLATE_H 5 | #define ROS_BABEL_FISH_MESSAGE_TEMPLATE_H 6 | 7 | #include "ros_babel_fish/message.h" 8 | 9 | #include 10 | #include 11 | 12 | namespace ros_babel_fish 13 | { 14 | 15 | struct MessageTemplate 16 | { 17 | typedef std::shared_ptr Ptr; 18 | typedef std::shared_ptr ConstPtr; 19 | 20 | MessageType type{}; 21 | std::map constants{}; 22 | struct 23 | { 24 | std::string datatype; 25 | std::vector names; 26 | std::vector types; 27 | } compound{}; 28 | struct 29 | { 30 | /*! 31 | * Length of the array. 32 | * -1 if dynamic size. 33 | */ 34 | ssize_t length; 35 | /*! 36 | * Type of the array elements. 37 | */ 38 | MessageType element_type; 39 | /*! 40 | * Element template for compound arrays 41 | */ 42 | MessageTemplate::ConstPtr element_template; 43 | } array{}; 44 | }; 45 | } // ros_babel_fish 46 | 47 | #endif //ROS_BABEL_FISH_MESSAGE_TEMPLATE_H 48 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/generation/providers/integrated_description_provider.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_INTEGRATED_DESCRIPTION_PROVIDER_H 5 | #define ROS_BABEL_FISH_INTEGRATED_DESCRIPTION_PROVIDER_H 6 | 7 | #include "ros_babel_fish/generation/description_provider.h" 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | /** 13 | * @brief C++ Reimplementation of message look ups and message definition / md5 sum generation 14 | */ 15 | class IntegratedDescriptionProvider : public DescriptionProvider 16 | { 17 | public: 18 | /** 19 | * @throws BabelFishException If the package paths could not be obtained which would render the description provider unable to serve its purpose 20 | */ 21 | IntegratedDescriptionProvider(); 22 | 23 | protected: 24 | MessageDescription::ConstPtr getMessageDescriptionImpl( const std::string &type ) override; 25 | 26 | ServiceDescription::ConstPtr getServiceDescriptionImpl( const std::string &type ) override; 27 | 28 | std::map> msg_paths_; 29 | std::map> srv_paths_; 30 | }; 31 | } // ros_babel_fish 32 | 33 | #endif // ROS_BABEL_FISH_INTEGRATED_DESCRIPTION_PROVIDER_H 34 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/message_info.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | 7 | using namespace ros_babel_fish; 8 | 9 | int main( int argc, char **argv ) 10 | { 11 | if ( argc != 2 ) 12 | { 13 | std::cout << "Invalid argument!" << std::endl; 14 | std::cout << "Usage: message_info [MESSAGE TYPE]" << std::endl; 15 | std::cout << "Example: message_info std_msgs/Header" << std::endl; 16 | return 1; 17 | } 18 | 19 | BabelFish babel_fish; 20 | MessageDescription::ConstPtr message_description = babel_fish.descriptionProvider()->getMessageDescription( argv[1] ); 21 | if ( message_description == nullptr ) 22 | { 23 | std::cerr << "No message definition for '" << argv[1] << "' found!" << std::endl; 24 | return 1; 25 | } 26 | std::cout << "Data Type:" << std::endl; 27 | std::cout << message_description->datatype << std::endl << std::endl; 28 | std::cout << "MD5:" << std::endl; 29 | std::cout << message_description->md5 << std::endl << std::endl; 30 | std::cout << "Message Definition:" << std::endl; 31 | std::cout << "======================" << std::endl; 32 | std::cout << message_description->message_definition; 33 | std::cout << "======================" << std::endl; 34 | std::cout << std::endl; 35 | } 36 | -------------------------------------------------------------------------------- /ros_babel_fish/test/service_client.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 04.09.19. 3 | // 4 | 5 | #include "message_comparison.h" 6 | 7 | #include 8 | 9 | #include 10 | #include 11 | 12 | using namespace ros_babel_fish; 13 | 14 | TEST( ServiceClientTest, tests ) 15 | { 16 | ros::service::waitForService( "/test_service_client/two_ints" ); 17 | BabelFish fish; 18 | Message::Ptr req = fish.createServiceRequest( "roscpp_tutorials/TwoInts" ); 19 | (*req)["a"] = 512; 20 | (*req)["b"] = 314; 21 | TranslatedMessage::Ptr res; 22 | ASSERT_TRUE( fish.callService( "/test_service_client/two_ints", req, res )); 23 | EXPECT_EQ((*res->translated_message)["sum"].value(), 868 ); // Sum is 512 + 314 + 42 = 868 24 | EXPECT_EQ( res->input_message->__getServiceDatatype(), "roscpp_tutorials/TwoInts" ); 25 | } 26 | 27 | TEST( ServiceTest, server ) 28 | { 29 | ros::service::waitForService( "/test_service_server/subscribers" ); 30 | rosapi::Subscribers subscribers; 31 | subscribers.request.topic = "First test"; 32 | EXPECT_TRUE( ros::service::call( "/test_service_server/subscribers", subscribers )); 33 | ASSERT_EQ( subscribers.response.subscribers.size(), 2UL ); 34 | EXPECT_EQ( subscribers.response.subscribers[0], "First test" ); 35 | EXPECT_EQ( subscribers.response.subscribers[1], "The answer to everything is:" ); 36 | } 37 | 38 | int main( int argc, char **argv ) 39 | { 40 | testing::InitGoogleTest( &argc, argv ); 41 | ros::init( argc, argv, "test_service_client" ); 42 | ros::NodeHandle nh; 43 | return RUN_ALL_TESTS(); 44 | } 45 | -------------------------------------------------------------------------------- /ros_babel_fish/test/action_client_test_server.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 03.03.20. 3 | // 4 | 5 | #include 6 | 7 | #include 8 | 9 | using namespace ros_babel_fish_test_msgs; 10 | 11 | actionlib::SimpleActionServer *simple_server; 12 | 13 | void simpleActionServerCallback( const SimpleTestGoalConstPtr &goal ) 14 | { 15 | for ( int i = 0; i < goal->goal; ++i ) 16 | { 17 | if ( i >= 10 && i >= goal->goal / 2 ) 18 | { 19 | SimpleTestResult result; 20 | result.result = i; 21 | simple_server->setAborted( result, "Failed to compute the answer to everything." ); 22 | return; 23 | } 24 | SimpleTestFeedback feedback; 25 | feedback.feedback = i; 26 | simple_server->publishFeedback( feedback ); 27 | usleep( 30000 ); 28 | if ( simple_server->isPreemptRequested()) 29 | { 30 | SimpleTestResult result; 31 | result.result = i; 32 | simple_server->setPreempted( result, "The answer to everything is:" ); 33 | return; 34 | } 35 | } 36 | SimpleTestResult result; 37 | result.result = goal->goal - 1; 38 | simple_server->setSucceeded( result ); 39 | } 40 | 41 | int main( int argc, char **argv ) 42 | { 43 | ros::init( argc, argv, "action_client_test_server" ); 44 | ros::NodeHandle nh_; 45 | simple_server = new actionlib::SimpleActionServer( nh_, "simple", &simpleActionServerCallback, 46 | false ); 47 | simple_server->start(); 48 | 49 | ros::spin(); 50 | return 0; 51 | } 52 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/actionlib/babel_fish_action.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_ACTION_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_ACTION_H 6 | 7 | #include "ros_babel_fish/actionlib/babel_fish_action_feedback.h" 8 | #include "ros_babel_fish/actionlib/babel_fish_action_goal.h" 9 | #include "ros_babel_fish/actionlib/babel_fish_action_result.h" 10 | 11 | namespace ros_babel_fish 12 | { 13 | 14 | template 15 | struct BabelFishAction_ 16 | { 17 | typedef BabelFishAction_ Type; 18 | 19 | BabelFishAction_() = default; 20 | 21 | explicit BabelFishAction_( const ContainerAllocator &allocator ) : action_goal( allocator ) { } 22 | 23 | typedef BabelFishActionGoal_ _action_goal_type; 24 | _action_goal_type action_goal; 25 | typedef BabelFishActionResult_ _action_result_type; 26 | _action_result_type action_result; 27 | typedef BabelFishActionFeedback_ _action_feedback_type; 28 | _action_feedback_type action_feedback; 29 | 30 | typedef boost::shared_ptr > Ptr; 31 | typedef boost::shared_ptr > ConstPtr; 32 | }; 33 | 34 | typedef BabelFishAction_ > BabelFishAction; 35 | } 36 | 37 | // Include specialization for ActionClient and SimpleActionClient 38 | #include "ros_babel_fish/actionlib/client/simple_action_client.h" 39 | 40 | #endif //ROS_BABEL_FISH_BABEL_FISH_ACTION_H 41 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/action_client.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | using namespace ros_babel_fish; 10 | 11 | int main( int argc, char **argv ) 12 | { 13 | ros::init( argc, argv, "ros_babel_fish_any_service_client" ); 14 | ros::NodeHandle nh; 15 | 16 | BabelFish fish; 17 | ros_babel_fish::MessageDescription::ConstPtr goal_description = fish.descriptionProvider()->getMessageDescription( 18 | "actionlib_tutorials/FibonacciActionGoal" ); 19 | actionlib::SimpleActionClient client( goal_description, "fibonacci" ); 20 | ROS_INFO( "Waiting for server to come up." ); 21 | if ( !client.waitForServer()) 22 | { 23 | ROS_ERROR( "Could not connect to server!" ); 24 | return 1; 25 | } 26 | // Create and translate goal 27 | Message::Ptr goal = fish.createMessage( "actionlib_tutorials/FibonacciGoal" ); 28 | (*goal)["order"] = 7; 29 | BabelFishMessage::ConstPtr msg = fish.translateMessage( goal ); 30 | 31 | ROS_INFO( "Sending goal." ); 32 | actionlib::SimpleClientGoalState goal_state = client.sendGoalAndWait( *msg ); 33 | std::cout << "Goal state: " << goal_state.getText() << std::endl; 34 | 35 | // Obtain result 36 | TranslatedMessage::Ptr result = fish.translateMessage( client.getResult()); 37 | auto &sequence = (*result->translated_message)["sequence"].as >(); 38 | 39 | // Print result sequence 40 | std::cout << "Result is an array of length:" << sequence.length() << std::endl; 41 | for ( size_t i = 0; i < sequence.length(); ++i ) 42 | { 43 | std::cout << sequence[i]; 44 | if ( i != sequence.length() - 1 ) std::cout << ", "; 45 | } 46 | std::cout << std::endl; 47 | } 48 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/messages/compound_message.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_COMPOUND_MESSAGE_H 5 | #define ROS_BABEL_FISH_COMPOUND_MESSAGE_H 6 | 7 | #include "ros_babel_fish/generation/message_template.h" 8 | #include "ros_babel_fish/message.h" 9 | 10 | #include 11 | 12 | namespace ros_babel_fish 13 | { 14 | 15 | class CompoundMessage : public Message 16 | { 17 | 18 | explicit CompoundMessage( const MessageTemplate::ConstPtr &msg_template, const uint8_t *stream ); 19 | 20 | public: 21 | typedef std::shared_ptr Ptr; 22 | typedef std::shared_ptr ConstPtr; 23 | 24 | static CompoundMessage *fromStream( const MessageTemplate::ConstPtr &msg_template, const uint8_t *stream, 25 | size_t stream_length, size_t &bytes_read ); 26 | 27 | explicit CompoundMessage( const MessageTemplate::ConstPtr &msg_template ); 28 | 29 | ~CompoundMessage() override; 30 | 31 | const std::string &datatype() const { return msg_template_->compound.datatype; } 32 | 33 | Message &operator[]( const std::string &key ) override; 34 | 35 | const Message &operator[]( const std::string &key ) const override; 36 | 37 | bool containsKey( const std::string &key ) const; 38 | 39 | const std::vector &keys() const { return msg_template_->compound.names; } 40 | 41 | const std::vector &values() const { return values_; } 42 | 43 | size_t _sizeInBytes() const override; 44 | 45 | bool isDetachedFromStream() const override; 46 | 47 | void detachFromStream() override; 48 | 49 | size_t writeToStream( uint8_t *stream ) const override; 50 | 51 | CompoundMessage &operator=( const CompoundMessage &other ); 52 | 53 | Message *clone() const override; 54 | 55 | protected: 56 | void assign( const Message &other ) override; 57 | 58 | private: 59 | MessageTemplate::ConstPtr msg_template_; 60 | std::vector values_; 61 | }; 62 | } // ros_babel_fish 63 | 64 | #endif //ROS_BABEL_FISH_COMPOUND_MESSAGE_H 65 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/service_info.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | 7 | using namespace ros_babel_fish; 8 | 9 | int main( int argc, char **argv ) 10 | { 11 | if ( argc != 2 ) 12 | { 13 | std::cout << "Invalid argument!" << std::endl; 14 | std::cout << "Usage: service_info [MESSAGE TYPE]" << std::endl; 15 | std::cout << "Example: service_info std_srvs/Trigger" << std::endl; 16 | return 1; 17 | } 18 | 19 | BabelFish babel_fish; 20 | ServiceDescription::ConstPtr message_description = babel_fish.descriptionProvider()->getServiceDescription( argv[1] ); 21 | if ( message_description == nullptr ) 22 | { 23 | std::cerr << "No service definition for '" << argv[1] << "' found!" << std::endl; 24 | return 1; 25 | } 26 | std::cout << "Data Type:" << std::endl; 27 | std::cout << message_description->datatype << std::endl << std::endl; 28 | std::cout << "MD5:" << std::endl; 29 | std::cout << message_description->md5 << std::endl << std::endl; 30 | std::cout << "Service specification:" << std::endl; 31 | std::cout << "======================" << std::endl; 32 | std::cout << message_description->specification; 33 | std::cout << "======================" << std::endl; 34 | std::cout << "Request:" << std::endl; 35 | std::cout << " Data Type:" << std::endl; 36 | std::cout << " " << message_description->request->datatype << std::endl; 37 | std::cout << " MD5:" << std::endl; 38 | std::cout << " " << message_description->request->md5 << std::endl; 39 | std::cout << " Message Definition:" << std::endl; 40 | std::cout << "======================" << std::endl; 41 | std::cout << " " << message_description->request->message_definition; 42 | std::cout << "======================" << std::endl; 43 | std::cout << "Response:" << std::endl; 44 | std::cout << " Data Type:" << std::endl; 45 | std::cout << " " << message_description->response->datatype << std::endl; 46 | std::cout << " MD5:" << std::endl; 47 | std::cout << " " << message_description->response->md5 << std::endl; 48 | std::cout << " Message Definition:" << std::endl; 49 | std::cout << "======================" << std::endl; 50 | std::cout << " " << message_description->response->message_definition; 51 | std::cout << "======================" << std::endl; 52 | std::cout << std::endl; 53 | } 54 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/generation/providers/message_only_description_provider.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MESSAGE_ONLY_DESCRIPTION_PROVIDER_H 5 | #define ROS_BABEL_FISH_MESSAGE_ONLY_DESCRIPTION_PROVIDER_H 6 | 7 | #include "ros_babel_fish/exceptions/babel_fish_exception.h" 8 | #include "ros_babel_fish/generation/description_provider.h" 9 | 10 | namespace ros_babel_fish 11 | { 12 | 13 | /** 14 | * @brief Simple and efficient DescriptionProvider that only operates on given messages. 15 | * 16 | * This implementation can only be used when receiving messages since it can only extract 17 | * message definitions from the registered messages. 18 | * It does not contain to look up unknown messages. 19 | */ 20 | class MessageOnlyDescriptionProvider : public DescriptionProvider 21 | { 22 | public: 23 | MessageOnlyDescriptionProvider() = default; 24 | 25 | /*! 26 | * This method registers a message and all its dependencies by its definition. 27 | * 28 | * @param type The datatype of the message. Example: std_msgs/Header 29 | * @param definition The definition of the message. This is the full definition including the the specifications of 30 | * all dependencies, i.e., messages this message depends on. 31 | */ 32 | MessageDescription::ConstPtr registerMessageByDefinition( const std::string &type, const std::string &definition ) 33 | { 34 | return DescriptionProvider::getMessageDescriptionImpl( type, definition ); 35 | } 36 | 37 | /*! 38 | * This method registers a message by its specification. This requires all dependencies to be either inbuilt types or 39 | * registered before. 40 | * 41 | * @param type The datatype of the message. Example: std_msgs/Header 42 | * @param specification The specification of the message. This is simply the specification what this specific message 43 | * contains without information about the used messages etc. 44 | */ 45 | MessageDescription::ConstPtr registerMessageBySpecification( const std::string &type, 46 | const std::string &specification ) 47 | { 48 | return DescriptionProvider::registerMessage( type, specification ); 49 | } 50 | 51 | protected: 52 | MessageDescription::ConstPtr getMessageDescriptionImpl( const std::string &type ) override 53 | { 54 | throw BabelFishException( 55 | "This description provider does not support look up for unknown messages and the message definition for " + type + 56 | " was not registered." ); 57 | } 58 | 59 | ServiceDescription::ConstPtr getServiceDescriptionImpl( const std::string &type ) override 60 | { 61 | throw BabelFishException( 62 | "This description provider does not support look up for unknown services and the service definition for " + type + 63 | " was not registered." ); 64 | } 65 | }; 66 | } // ros_babel_fish 67 | 68 | #endif //ROS_BABEL_FISH_MESSAGE_ONLY_DESCRIPTION_PROVIDER_H 69 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/messages/internal/value_compatibility.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2021 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_VALUE_COMPATIBILITY_H 5 | #define ROS_BABEL_FISH_VALUE_COMPATIBILITY_H 6 | 7 | #include 8 | 9 | namespace ros_babel_fish 10 | { 11 | //! Internal namespace not for public use, may change at any time. 12 | namespace internal 13 | { 14 | // Backport of C++20's std::remove_cvref 15 | template 16 | struct rm_cvref 17 | { 18 | typedef typename std::remove_cv::type>::type type; 19 | }; 20 | template 21 | using rm_cvref_t = typename rm_cvref::type; 22 | 23 | // is_integral is necessary to avoid a CLang tidy warning 24 | template 25 | typename std::enable_if< 26 | std::is_integral::value && 27 | std::numeric_limits::is_signed && !std::numeric_limits::is_signed, bool>::type 28 | constexpr inBounds( const T &val ) 29 | { 30 | return val >= 0 && static_cast::type >( val ) <= std::numeric_limits::max(); 31 | } 32 | 33 | template 34 | typename std::enable_if< 35 | std::is_integral::value && 36 | !std::numeric_limits::is_signed && std::numeric_limits::is_signed && 37 | std::numeric_limits::digits >= std::numeric_limits::digits, bool>::type 38 | constexpr inBounds( const T &val ) 39 | { 40 | return val <= static_cast(std::numeric_limits::max()); 41 | } 42 | 43 | template 44 | typename std::enable_if< 45 | std::is_integral::value && 46 | !std::numeric_limits::is_signed && std::numeric_limits::is_signed && 47 | std::numeric_limits::digits < std::numeric_limits::digits, bool>::type 48 | constexpr inBounds( const T &val ) 49 | { 50 | return static_cast(val) <= std::numeric_limits::max(); 51 | } 52 | 53 | template 54 | typename std::enable_if< 55 | std::is_integral::value && 56 | std::numeric_limits::is_signed == std::numeric_limits::is_signed, bool>::type 57 | constexpr inBounds( const T &val ) 58 | { 59 | return std::numeric_limits::min() <= val && val <= std::numeric_limits::max(); 60 | } 61 | 62 | template 63 | typename std::enable_if::value, bool>::type 64 | constexpr inBounds( const T &val ) 65 | { 66 | return static_cast(std::numeric_limits::min()) <= val && val <= static_cast(std::numeric_limits::max()); 67 | } 68 | 69 | /** 70 | * Returns true if type T can always be stored in U without overflowing. 71 | */ 72 | template 73 | typename std::enable_if::value && std::is_arithmetic::value, bool>::type 74 | constexpr isCompatible() 75 | { 76 | // See https://en.cppreference.com/w/cpp/types/numeric_limits/digits 77 | // + 1 added because ::digits returns nbits-1 for signed types. 78 | return std::is_same, rm_cvref_t>::value || 79 | std::is_floating_point::value || 80 | (std::is_integral::value && 81 | !(std::is_signed::value && std::is_unsigned::value) && 82 | (std::numeric_limits::digits + 1 < std::numeric_limits::digits)); 83 | } 84 | 85 | } 86 | } 87 | 88 | #endif //ROS_BABEL_FISH_VALUE_COMPATIBILITY_H 89 | -------------------------------------------------------------------------------- /ros_babel_fish/src/babel_fish_message.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "ros_babel_fish/babel_fish_message.h" 5 | 6 | namespace ros_babel_fish 7 | { 8 | BabelFishMessage::BabelFishMessage() 9 | : md5_( "*" ), server_md5_( "*" ), latched_( false ), buffer_( nullptr ), buffer_size_( 0 ), buffer_used_( 0 ) 10 | { 11 | } 12 | 13 | BabelFishMessage::BabelFishMessage( const BabelFishMessage &other ) 14 | : md5_( other.md5_ ), server_md5_( other.server_md5_ ), datatype_( other.datatype_ ) 15 | , service_datatype_( other.service_datatype_ ), definition_( other.definition_ ), latched_( other.latched_ ) 16 | , buffer_size_( other.buffer_used_ ), buffer_used_( other.buffer_used_ ) 17 | { 18 | buffer_ = new uint8_t[other.buffer_used_]; 19 | std::memcpy( buffer_, other.buffer_, other.buffer_used_ ); 20 | } 21 | 22 | BabelFishMessage &BabelFishMessage::operator=( const BabelFishMessage &other ) 23 | { 24 | if ( this == &other ) return *this; 25 | 26 | md5_ = other.md5_; 27 | server_md5_ = other.server_md5_; 28 | datatype_ = other.datatype_; 29 | service_datatype_ = other.service_datatype_; 30 | definition_ = other.definition_; 31 | latched_ = other.latched_; 32 | allocate( other.buffer_used_ ); 33 | std::memcpy( buffer_, other.buffer_, other.buffer_used_ ); 34 | return *this; 35 | } 36 | 37 | BabelFishMessage::~BabelFishMessage() 38 | { 39 | delete[] buffer_; 40 | 41 | buffer_ = nullptr; 42 | buffer_size_ = 0; 43 | buffer_used_ = 0; 44 | } 45 | 46 | const std::string &BabelFishMessage::md5Sum() const { return md5_; } 47 | 48 | const std::string &BabelFishMessage::dataType() const { return datatype_; } 49 | 50 | const std::string &BabelFishMessage::__getServerMD5Sum() const { return server_md5_; } 51 | 52 | const std::string &BabelFishMessage::__getServiceDatatype() const 53 | { 54 | if ( !service_datatype_.empty()) return service_datatype_; 55 | 56 | if ( strcmp( dataType().c_str() + dataType().length() - 7, "Request" ) == 0 ) 57 | { 58 | service_datatype_ = dataType().substr( 0, dataType().length() - 7 ); 59 | return service_datatype_; 60 | } 61 | if ( strcmp( dataType().c_str() + dataType().length() - 8, "Response" ) == 0 ) 62 | { 63 | service_datatype_ = dataType().substr( 0, dataType().length() - 8 ); 64 | return service_datatype_; 65 | } 66 | throw ros_babel_fish::BabelFishMessageException( 67 | "Tried to get service datatype for message that is not a service request or response! Datatype: " + dataType()); 68 | } 69 | 70 | const std::string &BabelFishMessage::definition() const { return definition_; } 71 | 72 | bool BabelFishMessage::isLatched() const { return latched_; } 73 | 74 | void BabelFishMessage::morph( const std::string &md5sum, const std::string &datatype, const std::string &definition, 75 | bool latched, const std::string &server_md5sum ) 76 | { 77 | md5_ = md5sum; 78 | server_md5_ = server_md5sum; 79 | datatype_ = datatype; 80 | definition_ = definition; 81 | latched_ = latched; 82 | } 83 | 84 | void BabelFishMessage::morph( const MessageDescription::ConstPtr &description, const std::string &server_md5sum ) 85 | { 86 | md5_ = description->md5; 87 | server_md5_ = server_md5sum; 88 | datatype_ = description->datatype; 89 | definition_ = description->message_definition; 90 | latched_ = false; 91 | } 92 | 93 | uint32_t BabelFishMessage::size() const 94 | { 95 | return buffer_used_; 96 | } 97 | 98 | void BabelFishMessage::allocate( size_t size ) 99 | { 100 | buffer_used_ = size; 101 | // Only reallocate if necessary 102 | if ( buffer_size_ > size ) return; 103 | delete[] buffer_; 104 | buffer_ = new uint8_t[size]; 105 | buffer_size_ = size; 106 | } 107 | } 108 | -------------------------------------------------------------------------------- /.travis.yml: -------------------------------------------------------------------------------- 1 | ################################################################################ 2 | 3 | cache: 4 | - apt 5 | 6 | # Build all valid Ubuntu/ROS combinations available on Travis VMs. 7 | language: cpp 8 | os: linux 9 | matrix: 10 | include: 11 | - name: "Bionic melodic AMD64" 12 | arch: amd64 13 | dist: bionic 14 | env: ROS_DISTRO=melodic 15 | - name: "Bionic melodic ARM64" 16 | arch: arm64 17 | dist: bionic 18 | env: ROS_DISTRO=melodic 19 | - name: "Focal noetic AMD64" 20 | arch: amd64 21 | dist: focal 22 | env: ROS_DISTRO=noetic 23 | - name: "Focal noetic ARM64" 24 | arch: arm64 25 | dist: focal 26 | env: ROS_DISTRO=noetic 27 | 28 | # Configuration variables. All variables are global now, but this can be used to 29 | # trigger a build matrix for different ROS distributions if desired. 30 | env: 31 | global: 32 | - ROS_CI_DESKTOP="`lsb_release -cs`" # e.g. [trusty|xenial|...] 33 | - CI_SOURCE_PATH=$(pwd) 34 | - ROS_PARALLEL_JOBS='-j8 -l6' 35 | # Set the python path manually to include /usr/-/python2.7/dist-packages 36 | # as this is where apt-get installs python packages. 37 | - PYTHONPATH=$PYTHONPATH:/usr/lib/python2.7/dist-packages:/usr/local/lib/python2.7/dist-packages 38 | 39 | ################################################################################ 40 | 41 | # Install system dependencies, namely a very barebones ROS setup. 42 | before_install: 43 | - sudo apt-get install dpkg curl 44 | - sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list" 45 | - curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add - 46 | - sudo apt-get update -qq 47 | - if [ $ROS_DISTRO = noetic ]; then PYTHON=python3; else PYTHON=python; fi 48 | - sudo apt-get install -y $PYTHON-catkin-pkg $PYTHON-catkin-tools $PYTHON-rosdep $PYTHON-wstool ros-$ROS_DISTRO-ros-base ros-$ROS_DISTRO-code-coverage 49 | - source /opt/ros/$ROS_DISTRO/setup.bash 50 | # Prepare rosdep to install dependencies. 51 | - sudo rosdep init 52 | - rosdep update 53 | 54 | # Create a catkin workspace with the package under integration. 55 | install: 56 | - mkdir -p ~/catkin_ws/src 57 | - cd ~/catkin_ws/src 58 | - catkin init 59 | # Create the devel/setup.bash (run catkin_make with an empty workspace) and 60 | # source it to set the path variables. 61 | - cd ~/catkin_ws 62 | - catkin config -j 2 # To avoid out-of-memory errors on build 63 | - CXXFLAGS=-Werror catkin build 64 | - source devel/setup.bash 65 | # Add the package under integration to the workspace using a symlink. 66 | - cd ~/catkin_ws/src 67 | - ln -s $CI_SOURCE_PATH . 68 | 69 | # Install all dependencies 70 | before_script: 71 | # package depdencies: install using rosdep. 72 | - cd ~/catkin_ws 73 | - rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO 74 | 75 | # Compile and test (mark the build as failed if any step fails). 76 | # 77 | # NOTE on testing: `catkin_make run_tests` will show the output of the tests 78 | # (gtest, nosetest, etc..) but always returns 0 (success) even if a test 79 | # fails. Running `catkin_test_results` aggregates all the results and returns 80 | # non-zero when a test fails (which notifies Travis the build failed). 81 | script: 82 | - source /opt/ros/$ROS_DISTRO/setup.bash 83 | - cd ~/catkin_ws 84 | - CXXFLAGS=-Werror catkin build 85 | # Run the tests, ensuring the path is set correctly. 86 | - source devel/setup.bash 87 | - catkin run_tests && catkin_test_results 88 | # Generate coverage 89 | - catkin clean -y 90 | - catkin build ros_babel_fish -DENABLE_COVERAGE_TESTING=ON -DCMAKE_BUILD_TYPE=Debug 91 | - catkin build ros_babel_fish --no-deps -DENABLE_COVERAGE_TESTING=ON -DCMAKE_BUILD_TYPE=Debug -v --catkin-make-args ros_babel_fish_coverage 92 | - bash <(curl -s https://codecov.io/bash) -f ./build/ros_babel_fish/ros_babel_fish_coverage.info -R ./src/ros_babel_fish 93 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/any_publisher.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | /*! 11 | * The following example demonstrates how messages can be published without knowing their type. 12 | */ 13 | 14 | using namespace ros_babel_fish; 15 | 16 | int main( int argc, char **argv ) 17 | { 18 | ros::init( argc, argv, "ros_babel_fish_publish_string" ); 19 | ros::NodeHandle nh; 20 | 21 | BabelFish fish; 22 | 23 | // Publish a string message 24 | ros::Publisher pub_string = fish.advertise( nh, "std_msgs/String", "/string", 1, true ); 25 | { 26 | Message::Ptr message = fish.createMessage( "std_msgs/String" ); 27 | (*message)["data"] = "Hello World!"; 28 | 29 | BabelFishMessage::Ptr translated_message = fish.translateMessage( message ); 30 | pub_string.publish( translated_message ); 31 | } 32 | 33 | // Publish a Pose 34 | ros::Publisher pub_pose = fish.advertise( nh, "geometry_msgs/Pose", "/pose", 1, true ); 35 | { 36 | Message::Ptr message = fish.createMessage( "geometry_msgs/Pose" ); 37 | auto &compound = message->as(); 38 | // Different methods of assigning the values 39 | // Access without convenience functions 40 | compound.as()["position"].as()["x"].as>().setValue( 2.4 ); 41 | // This access can be shorted using convenience methods to 42 | compound["position"]["y"].as>().setValue( 1.1 ); 43 | // which evaluates to the same as the access above. It can be shortened even further to 44 | compound["position"]["z"] = 3.6; 45 | // where you should pay attention to the datatype. It will be casted to the actual type of the ValueMessage but 46 | // this may throw an exception if not possible, e.g., bool, string, time and duration can not be assigned to a 47 | // different type. If it may result in a loss of information, e.g., assigning a double value to a int32 field, 48 | // a warning is printed and it should be avoided. If it does result in a loss of information, e.g., out of the 49 | // target types bounds or assigning a double value to a float ValueMessage, it will throw an exception. 50 | 51 | compound["orientation"]["w"] = 0.384; 52 | compound["orientation"]["x"] = -0.003; 53 | compound["orientation"]["y"] = -0.876; 54 | compound["orientation"]["z"] = 0.292; 55 | 56 | BabelFishMessage::Ptr translated_message = fish.translateMessage( message ); 57 | pub_pose.publish( translated_message ); 58 | } 59 | 60 | BabelFish fish2; 61 | // Publish a Pose with covariance (has fixed array size) 62 | ros::Publisher pub_posewcv = fish2.advertise( nh, "geometry_msgs/PoseWithCovariance", "/pose_with_covariance", 1, 63 | true ); 64 | { 65 | Message::Ptr message = fish2.createMessage( "geometry_msgs/PoseWithCovariance" ); 66 | auto &compound = message->as(); 67 | compound["pose"]["position"]["x"].as>().setValue( 1.1 ); 68 | compound["pose"]["position"]["y"].as>().setValue( 2.4 ); 69 | compound["pose"]["position"]["z"].as>().setValue( 3.1 ); 70 | 71 | 72 | compound["pose"]["orientation"]["w"].as>().setValue( 0.384 ); 73 | compound["pose"]["orientation"]["x"].as>().setValue( -0.003 ); 74 | compound["pose"]["orientation"]["y"].as>().setValue( -0.876 ); 75 | compound["pose"]["orientation"]["z"].as>().setValue( 0.292 ); 76 | 77 | auto &covariance = compound["covariance"].as>(); 78 | for ( size_t i = 0; i < covariance.length(); ++i ) 79 | { 80 | covariance.assign( i, static_cast(i)); 81 | } 82 | 83 | BabelFishMessage::Ptr translated_message = fish2.translateMessage( message ); 84 | pub_posewcv.publish( translated_message ); 85 | } 86 | 87 | ROS_INFO( "Staying alive for 3 seconds." ); 88 | ros::WallDuration( 3 ).sleep(); 89 | } 90 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/rosbag_frame_ids.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | #include 14 | 15 | /*! 16 | * The following example demonstrates efficient processing of messages of unspecified type in a rosbag. 17 | * Given a rosbag as input, dumps the frame_id for each topic that has a header. 18 | */ 19 | 20 | using namespace ros_babel_fish; 21 | 22 | /*! 23 | * Thin wrapper around rosbag::MessageInstance to make it compatible with BabelFishMessage. 24 | * This avoids the need for a conversion to a BabelFishMessage instance, which would mean always copying 25 | * the message body, definition, type name, etc for each individual message. 26 | * Instead, only the message body is lazily read from the bag when necessary. 27 | */ 28 | class RosbagBabelFishMessage : public IBabelFishMessage 29 | { 30 | public: 31 | // Always copy the MessageInstance since it pretty much only contains pointers. 32 | RosbagBabelFishMessage( rosbag::MessageInstance msg ) : mi_( std::move( msg )) { } 33 | 34 | const std::string &topic() const { return mi_.getTopic(); } 35 | 36 | const std::string &md5Sum() const final { return mi_.getMD5Sum(); } 37 | 38 | const std::string &dataType() const final { return mi_.getDataType(); } 39 | 40 | const std::string &definition() const final { return mi_.getMessageDefinition(); } 41 | 42 | bool isLatched() const final { return mi_.isLatching(); } 43 | 44 | std::string callerId() const { return mi_.getCallerId(); } 45 | 46 | uint32_t size() const final { return mi_.size(); } 47 | 48 | const uint8_t *buffer() const final 49 | { 50 | if ( buffer_.empty() and size() > 0 ) 51 | { 52 | buffer_.resize( size()); 53 | ros::serialization::OStream stream( buffer_.data(), buffer_.size()); 54 | mi_.write( stream ); 55 | } 56 | return buffer_.data(); 57 | } 58 | 59 | template 60 | boost::shared_ptr instantiate() const { mi_.template instantiate(); } 61 | 62 | private: 63 | const rosbag::MessageInstance mi_; 64 | mutable std::vector buffer_; 65 | }; 66 | 67 | int main( int argc, char **argv ) 68 | { 69 | if ( argc != 2 ) 70 | { 71 | std::cout << "Invalid argument!" << std::endl; 72 | std::cout << "Usage: rosbag [BAG]" << std::endl; 73 | return 1; 74 | } 75 | 76 | auto description_provider = std::make_shared(); 77 | BabelFish fish( description_provider ); 78 | MessageExtractor extractor( fish ); 79 | 80 | rosbag::Bag bag( argv[1] ); 81 | rosbag::View view( bag ); 82 | 83 | // Get the set of relevant topics. 84 | // Also populates the MessageOnlyDescriptionProvider object with all message definitions in the given bag. 85 | std::unordered_set topics; 86 | for ( const auto &c : view.getConnections()) 87 | { 88 | auto desc = description_provider->getMessageDescription( c->datatype, c->md5sum, c->msg_def ); 89 | const auto &field_names = desc->message_template->compound.names; 90 | if ( std::find( field_names.begin(), field_names.end(), "header" ) != field_names.end()) 91 | topics.insert( c->topic ); 92 | } 93 | 94 | for ( const rosbag::MessageInstance &mi: view ) 95 | { 96 | if ( topics.empty()) 97 | break; 98 | if ( topics.find( mi.getTopic()) == topics.end()) 99 | continue; 100 | RosbagBabelFishMessage msg( mi ); 101 | // Not that useful here, but the field location should usually be cached based on the message type. 102 | SubMessageLocation location = extractor.retrieveLocationForPath( msg, "header.frame_id" ); 103 | auto frame_id = extractor.extractValue( msg, location ); 104 | std::cout << msg.topic() << ": " << frame_id << std::endl; 105 | topics.erase( msg.topic()); 106 | } 107 | bag.close(); 108 | } 109 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/generation/description_provider.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_DESCRIPTION_PROVIDER_H 5 | #define ROS_BABEL_FISH_DESCRIPTION_PROVIDER_H 6 | 7 | #include "ros_babel_fish/babel_fish_message.h" 8 | #include "ros_babel_fish/message_description.h" 9 | 10 | #include 11 | 12 | namespace ros_babel_fish 13 | { 14 | 15 | class DescriptionProvider 16 | { 17 | protected: 18 | struct MessageSpec 19 | { 20 | struct Constant 21 | { 22 | std::string type; 23 | std::string name; 24 | std::string val; 25 | }; 26 | std::string name; 27 | std::string package; 28 | std::string text; 29 | std::vector constants; 30 | std::vector types; 31 | std::vector names; 32 | std::vector dependencies; 33 | std::string md5; 34 | }; 35 | public: 36 | typedef std::shared_ptr Ptr; 37 | 38 | DescriptionProvider(); 39 | 40 | virtual ~DescriptionProvider() = default; 41 | 42 | MessageDescription::ConstPtr getMessageDescription( const std::string &type ); 43 | 44 | MessageDescription::ConstPtr getMessageDescription( const IBabelFishMessage &msg ); 45 | 46 | MessageDescription::ConstPtr getMessageDescription( const std::string &type, const std::string &md5, 47 | const std::string &definition ); 48 | 49 | ServiceDescription::ConstPtr getServiceDescription( const std::string &type ); 50 | 51 | bool isBuiltIn( const std::string &type ) const; 52 | 53 | protected: 54 | 55 | virtual MessageDescription::ConstPtr getMessageDescriptionImpl( const std::string &type ) = 0; 56 | 57 | virtual MessageDescription::ConstPtr getMessageDescriptionImpl( const std::string &type, 58 | const std::string &definition ); 59 | 60 | virtual MessageDescription::ConstPtr getMessageDescriptionImpl( const IBabelFishMessage &msg ); 61 | 62 | virtual ServiceDescription::ConstPtr getServiceDescriptionImpl( const std::string &type ) = 0; 63 | 64 | MessageTemplate::Ptr createTemplate( const MessageSpec &spec ); 65 | 66 | MessageDescription::ConstPtr registerMessage( const MessageSpec &spec, const std::string &definition ); 67 | 68 | MessageDescription::ConstPtr registerMessage( const std::string &type, const std::string &definition, 69 | const std::string &md5, const std::string &specification ); 70 | 71 | MessageDescription::ConstPtr registerMessage( const std::string &type, const std::string &specification ); 72 | 73 | ServiceDescription::ConstPtr registerService( const std::string &type, const std::string &md5, 74 | const std::string &specification, 75 | const MessageSpec &req_spec, const std::string &req_definition, 76 | const MessageSpec &resp_spec, const std::string &resp_definition ); 77 | 78 | ServiceDescription::ConstPtr registerService( const std::string &type, const std::string &specification, 79 | const std::string &req_specification, 80 | const std::string &resp_specification ); 81 | 82 | MessageSpec createSpec( const std::string &type, const std::string &package, const std::string &specification ); 83 | 84 | std::vector getAllDepends( const MessageSpec &spec ); 85 | 86 | void loadDependencies( const MessageSpec &spec ); 87 | 88 | std::string computeFullText( const MessageSpec &spec ); 89 | 90 | std::string computeMD5Text( const MessageSpec &spec ); 91 | 92 | private: 93 | void initBuiltInTypes(); 94 | 95 | 96 | std::unordered_map msg_specs_; 97 | std::unordered_map message_descriptions_; 98 | std::unordered_map service_descriptions_; 99 | std::set builtin_types_; 100 | }; 101 | } // ros_babel_fish 102 | 103 | #endif // ROS_BABEL_FISH_DESCRIPTION_PROVIDER_H 104 | -------------------------------------------------------------------------------- /ros_babel_fish/src/generation/message_creation.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include "ros_babel_fish/generation/message_creation.h" 6 | 7 | #include "ros_babel_fish/messages/array_message.h" 8 | #include "ros_babel_fish/messages/compound_message.h" 9 | #include "ros_babel_fish/messages/value_message.h" 10 | 11 | namespace ros_babel_fish 12 | { 13 | 14 | Message *createValueMessageFromDataRaw( MessageType type, const uint8_t *stream, size_t &bytes_read ) 15 | { 16 | using namespace message_type_traits; 17 | constexpr size_t limit = std::numeric_limits::max(); 18 | switch ( type ) 19 | { 20 | case MessageTypes::Bool: 21 | return ValueMessage::value>::fromStream( stream, 1, bytes_read ); 22 | case MessageTypes::UInt8: 23 | return ValueMessage::value>::fromStream( stream, 1, bytes_read ); 24 | case MessageTypes::UInt16: 25 | return ValueMessage::value>::fromStream( stream, 2, bytes_read ); 26 | case MessageTypes::UInt32: 27 | return ValueMessage::value>::fromStream( stream, 4, bytes_read ); 28 | case MessageTypes::UInt64: 29 | return ValueMessage::value>::fromStream( stream, 8, bytes_read ); 30 | case MessageTypes::Int8: 31 | return ValueMessage::value>::fromStream( stream, 1, bytes_read ); 32 | case MessageTypes::Int16: 33 | return ValueMessage::value>::fromStream( stream, 2, bytes_read ); 34 | case MessageTypes::Int32: 35 | return ValueMessage::value>::fromStream( stream, 4, bytes_read ); 36 | case MessageTypes::Int64: 37 | return ValueMessage::value>::fromStream( stream, 8, bytes_read ); 38 | case MessageTypes::Float32: 39 | return ValueMessage::value>::fromStream( stream, 4, bytes_read ); 40 | case MessageTypes::Float64: 41 | return ValueMessage::value>::fromStream( stream, 8, bytes_read ); 42 | case MessageTypes::String: 43 | return ValueMessage::value>::fromStream( stream, limit, bytes_read ); 44 | case MessageTypes::Time: 45 | return ValueMessage::value>::fromStream( stream, 8, bytes_read ); 46 | case MessageTypes::Duration: 47 | return ValueMessage::value>::fromStream( stream, 8, bytes_read ); 48 | case MessageTypes::Compound: 49 | case MessageTypes::Array: 50 | throw BabelFishException( "Array and compound are not value message types!" ); 51 | default: 52 | throw BabelFishException( "Can not create value message from unknown message type!" ); 53 | } 54 | } 55 | 56 | Message::Ptr createValueMessageFromData( MessageType type, const uint8_t *stream, size_t &bytes_read ) 57 | { 58 | return Message::Ptr( createValueMessageFromDataRaw( type, stream, bytes_read )); 59 | } 60 | 61 | Message *createMessageFromTemplateRaw( const MessageTemplate::ConstPtr &msg_template, const uint8_t *stream, 62 | size_t length, size_t &bytes_read ) 63 | { 64 | return CompoundMessage::fromStream( msg_template, stream, length, bytes_read ); 65 | } 66 | 67 | Message::Ptr createMessageFromTemplate( const MessageTemplate::ConstPtr &msg_template, const uint8_t *stream, 68 | size_t length, size_t &bytes_read ) 69 | { 70 | bytes_read = 0; 71 | if ( stream == nullptr ) return Message::Ptr( createEmptyMessageFromTemplate( msg_template )); 72 | return Message::Ptr( createMessageFromTemplateRaw( msg_template, stream, length, bytes_read )); 73 | } 74 | 75 | Message *createEmptyMessageFromTemplateRaw( const MessageTemplate::ConstPtr &msg_template ) 76 | { 77 | return new CompoundMessage( msg_template ); 78 | } 79 | 80 | Message::Ptr createEmptyMessageFromTemplate( const MessageTemplate::ConstPtr &msg_template ) 81 | { 82 | return Message::Ptr( createEmptyMessageFromTemplateRaw( msg_template )); 83 | } 84 | } 85 | -------------------------------------------------------------------------------- /ros_babel_fish/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package ros_babel_fish 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.9.3 (2022-04-20) 6 | ------------------ 7 | * Added some more information to exception messages. 8 | * Add libssl-dev as a build-export dependency 9 | * Contributors: AR Dabbour, Stefan Fabian 10 | 11 | 0.9.2 (2021-12-22) 12 | ------------------ 13 | * Better rosbag support + example (`#7 `_) 14 | * Accept a more general IBabelFishMessage interface in read-only functions. 15 | * Add a rosbag example, add some useful method overloads. 16 | * Add noetic to CI, improvements to type safety checking (`#6 `_) 17 | * Add noetic to CI. 18 | * Simplify isCompatible() and inBounds() checks, add tests. 19 | * Moved compatibility checks to header and internal namespace. 20 | Co-authored-by: Stefan Fabian 21 | * Accept True and False as boolean constants (`#4 `_) 22 | Co-authored-by: Stefan Fabian 23 | * Added more explicit warning if message type is not a valid message name. 24 | * Made BabelFishMessageException subclass of BabelFishException. 25 | * Contributors: Martin Valgur, Stefan Fabian 26 | 27 | 0.9.1 (2020-10-29) 28 | ------------------ 29 | * Added missing build depend for openssl headers to fix build for noetic. 30 | * Contributors: Stefan Fabian 31 | 32 | 0.9.0 (2020-10-28) 33 | ------------------ 34 | * Added install target for service_info. Cleaned up package.xml 35 | * Fixed service spec loading wrong response if service spec doesn't contain '---'. 36 | * Updated integrated description provider for service descriptions to reflect changes in genmsg that caused some tests to fail. 37 | Both implementations are interoperable and the change should have no impact on service calls using ros_babel_fish but new implementation is now again consistent with message_traits::definition<...>(). 38 | The new implementation is also less complex and faster. 39 | * Added macros for template calls. 40 | This replaces the boiler plate code for situations where you would do switch(msg.type()) { ... } and call a template function with the C++ type of the message as a template parameter. 41 | * Contributors: Stefan Fabian 42 | 43 | 0.8.0 (2020-03-20) 44 | ------------------ 45 | * Updated install targets and added OpenSSL to dependencies. 46 | * Added support for lookups from devel spaces. 47 | * Changed action client specialization default values for queue sizes to prevent information loss. 48 | * Added missing typedefs. 49 | * Added specialization for action client to allow creating an ActionClient with a BabelFishAction. 50 | * Renamed size and data to more descriptive names _sizeInBytes and _stream. 51 | size and data will be removed in future release. 52 | * Configuration for Travis and CodeCov. Added test depends. Set CMake min to 3.0 which should work with kinetic but due to the tests requiring melodic, kinetic will remain officially unsupported even though it should work. 53 | * Removed embedded python description provider. Improved description provider performance. 54 | * Moved message from stream creation to static fromStream method. 55 | CompoundMessage now uses template to auto-initialize for easier message construction. 56 | Changed ArrayMessage interface to use vector-like interface. Old methods deprecated and will be removed in a future version. 57 | * Renamed targets to include ${PROJECT_NAME} prefix to fix `#3 `_. 58 | * Moved benchmarks to separate repo. 59 | * Added message extractor. 60 | Updated benchmarks with results for message extractor. 61 | Fixed examples using old array structure. 62 | * Added integrated description provider. 63 | Added deprecated built-ins byte and char. 64 | Added benchmark. 65 | * More error checking for embedded python. 66 | * Updated description for initial release. 67 | * Commented action stuff which is not yet ready for release. 68 | * Merge branch 'master' of github.com:StefanFabian/ros_babel_fish 69 | * Cleanup for initial release. 70 | Added convenience methods. 71 | Added a lot of tests. 72 | * Cleanup for initial release. 73 | Added convenience methods. 74 | Added a lot of tests. 75 | * Added error handling for unknown service. Added special CompoundArrayMessage subclass to provide the element's datatype. 76 | * Added bool as explicit type. 77 | * Initial commit 78 | * Contributors: Stefan Fabian 79 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/messages/value_message.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_VALUE_MESSAGE_H 5 | #define ROS_BABEL_FISH_VALUE_MESSAGE_H 6 | 7 | #include "ros_babel_fish/exceptions/babel_fish_exception.h" 8 | #include "ros_babel_fish/message.h" 9 | 10 | #include 11 | 12 | namespace ros_babel_fish 13 | { 14 | 15 | template 16 | class ValueMessage : public Message 17 | { 18 | static constexpr MessageType type = message_type_traits::message_type::value; 19 | static_assert( type != MessageTypes::None, "Invalid type parameter for ValueMessage!" ); 20 | public: 21 | explicit ValueMessage( T value = T()) 22 | : Message( type ), value_( value ), from_stream_( false ) { } 23 | 24 | explicit ValueMessage( const uint8_t *stream ) 25 | : Message( type, stream ), value_( T()), from_stream_( stream != nullptr ) { } 26 | 27 | T getValue() const 28 | { 29 | if ( from_stream_ ) return *reinterpret_cast(stream_); 30 | return value_; 31 | } 32 | 33 | void setValue( T value ) 34 | { 35 | value_ = value; 36 | from_stream_ = false; 37 | } 38 | 39 | size_t _sizeInBytes() const override { return sizeof( T ); } 40 | 41 | bool isDetachedFromStream() const override 42 | { 43 | return !from_stream_; 44 | } 45 | 46 | void detachFromStream() override 47 | { 48 | if ( !from_stream_ ) return; 49 | value_ = getValue(); 50 | from_stream_ = false; 51 | } 52 | 53 | size_t writeToStream( uint8_t *stream ) const override 54 | { 55 | *reinterpret_cast(stream) = getValue(); 56 | return sizeof( T ); 57 | } 58 | 59 | static ValueMessage *fromStream( const uint8_t *stream, size_t stream_length, size_t &bytes_read ) 60 | { 61 | (void) stream_length; // For unused warning 62 | T val = *reinterpret_cast(stream + bytes_read); 63 | bytes_read += sizeof( T ); 64 | if ( bytes_read > stream_length ) 65 | throw BabelFishException( "Unexpected end of stream while reading message from stream!" ); 66 | return new ValueMessage( val ); 67 | } 68 | 69 | ValueMessage &operator=( const T &value ) 70 | { 71 | setValue( value ); 72 | return *this; 73 | } 74 | 75 | ValueMessage &operator=( const ValueMessage &other ) 76 | { 77 | setValue( other.getValue()); 78 | return *this; 79 | } 80 | 81 | Message *clone() const override 82 | { 83 | if ( isDetachedFromStream()) return new ValueMessage( getValue()); 84 | return new ValueMessage( stream_ ); 85 | } 86 | 87 | protected: 88 | void assign( const Message &other ) override 89 | { 90 | if ( type != other.type()) throw BabelFishException( "Tried to assign incompatible message to ValueMessage!" ); 91 | setValue( other.as>().getValue()); 92 | } 93 | 94 | mutable T value_; 95 | mutable bool from_stream_; 96 | }; 97 | 98 | // Bool specialization 99 | template<> 100 | bool ValueMessage::getValue() const; 101 | 102 | template<> 103 | size_t ValueMessage::_sizeInBytes() const; 104 | 105 | template<> 106 | ValueMessage *ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, size_t &bytes_read ); 107 | 108 | template<> 109 | size_t ValueMessage::writeToStream( uint8_t *stream ) const; 110 | 111 | // Time specialization 112 | template<> 113 | ros::Time ValueMessage::getValue() const; 114 | 115 | template<> 116 | size_t ValueMessage::_sizeInBytes() const; 117 | 118 | template<> 119 | ValueMessage * 120 | ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, size_t &bytes_read ); 121 | 122 | template<> 123 | size_t ValueMessage::writeToStream( uint8_t *stream ) const; 124 | 125 | // Duration specialization 126 | template<> 127 | ros::Duration ValueMessage::getValue() const; 128 | 129 | template<> 130 | size_t ValueMessage::_sizeInBytes() const; 131 | 132 | template<> 133 | ValueMessage * 134 | ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, size_t &bytes_read ); 135 | 136 | template<> 137 | size_t ValueMessage::writeToStream( uint8_t *stream ) const; 138 | 139 | // String specialization 140 | template<> 141 | std::string ValueMessage::getValue() const; 142 | 143 | template<> 144 | size_t ValueMessage::_sizeInBytes() const; 145 | 146 | template<> 147 | ValueMessage * 148 | ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, size_t &bytes_read ); 149 | 150 | template<> 151 | size_t ValueMessage::writeToStream( uint8_t *stream ) const; 152 | } // ros_babel_fish 153 | 154 | #endif //ROS_BABEL_FISH_VALUE_MESSAGE_H 155 | -------------------------------------------------------------------------------- /ros_babel_fish/test/action_client.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 03.03.20. 3 | // 4 | 5 | #include "message_comparison.h" 6 | #include 7 | #include 8 | #include 9 | 10 | using namespace ros_babel_fish; 11 | using namespace ros_babel_fish_test_msgs; 12 | 13 | TEST( ActionClientTest, actionLookup ) 14 | { 15 | BabelFish fish; 16 | // Actions are autogenerated and for source packages lie in the devel space. 17 | // This tests that msg descriptions in the devel space are found. 18 | MessageDescription::ConstPtr description = 19 | fish.descriptionProvider()->getMessageDescription( "ros_babel_fish_test_msgs/SimpleTestActionGoal" ); 20 | EXPECT_NE( description, nullptr ); 21 | } 22 | 23 | TEST( ActionClientTest, simpleActionClient ) 24 | { 25 | auto provider = std::make_shared(); 26 | BabelFish fish( provider ); 27 | provider->registerMessageByDefinition( ros::message_traits::datatype(), 28 | ros::message_traits::definition()); 29 | MessageDescription::ConstPtr goal_description = provider->getMessageDescription( 30 | ros::message_traits::datatype()); 31 | actionlib::SimpleActionClient client( goal_description, "simple" ); 32 | if ( !client.waitForServer( ros::Duration( 10 ))) 33 | FAIL() << "ActionServer did not start within 10 seconds!"; 34 | ASSERT_TRUE( client.isServerConnected()); 35 | 36 | // This goal should succeed 37 | Message::Ptr goal = fish.createMessage( "ros_babel_fish_test_msgs/SimpleTestGoal" ); 38 | (*goal)["goal"] = 5; 39 | BabelFishMessage::ConstPtr goal_msg = fish.translateMessage( goal ); 40 | actionlib::SimpleClientGoalState state = client.sendGoalAndWait( *goal_msg, ros::Duration( 10 )); 41 | EXPECT_EQ( state, actionlib::SimpleClientGoalState::SUCCEEDED ); 42 | BabelFishMessage::ConstPtr result = client.getResult(); 43 | TranslatedMessage::ConstPtr translated = fish.translateMessage( result ); 44 | EXPECT_EQ((*translated->translated_message)["result"].value(), 4 ); 45 | 46 | // This goal should abort after 10 47 | goal = fish.createMessage( "ros_babel_fish_test_msgs/SimpleTestGoal" ); 48 | (*goal)["goal"] = 20; 49 | goal_msg = fish.translateMessage( goal ); 50 | std::vector feedback_values; 51 | client.sendGoal( *goal_msg, {}, {}, boost::function( 52 | [ & ]( const BabelFishMessage::ConstPtr &feedback ) 53 | { 54 | TranslatedMessage::ConstPtr translated = fish.translateMessage( feedback ); 55 | feedback_values.push_back((*translated->translated_message)["feedback"].value()); 56 | } )); 57 | ASSERT_EQ( client.getState(), actionlib::SimpleClientGoalState::PENDING ); 58 | if ( !client.waitForResult( ros::Duration( 10 ))) 59 | { 60 | FAIL() << "ActionServer did not finish in 10 seconds!"; 61 | } 62 | ASSERT_EQ( feedback_values.size(), 10U ); 63 | for ( int i = 0; i < 10; ++i ) 64 | { 65 | if ( feedback_values[i] != i ) FAIL() << "Feedback at " << i << " should be " << i << "!"; 66 | } 67 | EXPECT_EQ( client.getState(), actionlib::SimpleClientGoalState::ABORTED ); 68 | result = client.getResult(); 69 | translated = fish.translateMessage( result ); 70 | EXPECT_EQ((*translated->translated_message)["result"].value(), 10 ); 71 | 72 | // This goal should be preempted 73 | goal = fish.createMessage( "ros_babel_fish_test_msgs/SimpleTestGoal" ); 74 | (*goal)["goal"] = 1000; 75 | goal_msg = fish.translateMessage( goal ); 76 | feedback_values.clear(); 77 | client.sendGoal( *goal_msg, {}, {}, boost::function( 78 | [ & ]( const BabelFishMessage::ConstPtr &feedback ) 79 | { 80 | TranslatedMessage::ConstPtr translated = fish.translateMessage( feedback ); 81 | feedback_values.push_back((*translated->translated_message)["feedback"].value()); 82 | } )); 83 | usleep( 500000 ); // Sleep for 500ms 84 | client.cancelGoal(); 85 | if ( !client.waitForResult( ros::Duration( 1 ))) 86 | FAIL() << "ActionServer did not preempt in 1 second!"; 87 | int last_feedback = 0; 88 | for ( size_t i = 0; i < feedback_values.size(); ++i ) 89 | { 90 | if ( feedback_values[i] != int( i )) FAIL() << "Feedback at " << i << " should be " << i << "!"; 91 | last_feedback = feedback_values[i]; 92 | } 93 | EXPECT_EQ( client.getState(), actionlib::SimpleClientGoalState::PREEMPTED ); 94 | result = client.getResult(); 95 | translated = fish.translateMessage( result ); 96 | EXPECT_EQ((*translated->translated_message)["result"].value(), last_feedback ); 97 | } 98 | 99 | int main( int argc, char **argv ) 100 | { 101 | testing::InitGoogleTest( &argc, argv ); 102 | ros::init( argc, argv, "test_action_client" ); 103 | ros::NodeHandle nh; 104 | return RUN_ALL_TESTS(); 105 | } 106 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/macros.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MACROS_H 5 | #define ROS_BABEL_FISH_MACROS_H 6 | 7 | #define RBF_TEMPLATE_CALL( function, type, args... ) { \ 8 | switch (type) \ 9 | { \ 10 | case MessageTypes::Compound: \ 11 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 12 | break; \ 13 | case MessageTypes::Array: \ 14 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 15 | break; \ 16 | case MessageTypes::Bool: \ 17 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 18 | break; \ 19 | case MessageTypes::UInt8: \ 20 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 21 | break; \ 22 | case MessageTypes::UInt16: \ 23 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 24 | break; \ 25 | case MessageTypes::UInt32: \ 26 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 27 | break; \ 28 | case MessageTypes::UInt64: \ 29 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 30 | break; \ 31 | case MessageTypes::Int8: \ 32 | function<::ros_babel_fish::message_type_traits::member_type::value>( args ); \ 33 | break; \ 34 | case MessageTypes::Int16: \ 35 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 36 | break; \ 37 | case MessageTypes::Int32: \ 38 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 39 | break; \ 40 | case MessageTypes::Int64: \ 41 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 42 | break; \ 43 | case MessageTypes::Float32: \ 44 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 45 | break; \ 46 | case MessageTypes::Float64: \ 47 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 48 | break; \ 49 | case MessageTypes::String: \ 50 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 51 | break; \ 52 | case MessageTypes::Time: \ 53 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 54 | break; \ 55 | case MessageTypes::Duration: \ 56 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 57 | break; \ 58 | } \ 59 | } 60 | 61 | #define RBF_TEMPLATE_CALL_VALUE_TYPES( function, type, args... ) { \ 62 | switch (type) \ 63 | { \ 64 | case MessageTypes::Bool: \ 65 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 66 | break; \ 67 | case MessageTypes::UInt8: \ 68 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 69 | break; \ 70 | case MessageTypes::UInt16: \ 71 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 72 | break; \ 73 | case MessageTypes::UInt32: \ 74 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 75 | break; \ 76 | case MessageTypes::UInt64: \ 77 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 78 | break; \ 79 | case MessageTypes::Int8: \ 80 | function<::ros_babel_fish::message_type_traits::member_type::value>( args ); \ 81 | break; \ 82 | case MessageTypes::Int16: \ 83 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 84 | break; \ 85 | case MessageTypes::Int32: \ 86 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 87 | break; \ 88 | case MessageTypes::Int64: \ 89 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 90 | break; \ 91 | case MessageTypes::Float32: \ 92 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 93 | break; \ 94 | case MessageTypes::Float64: \ 95 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 96 | break; \ 97 | case MessageTypes::String: \ 98 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 99 | break; \ 100 | case MessageTypes::Time: \ 101 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 102 | break; \ 103 | case MessageTypes::Duration: \ 104 | function<::ros_babel_fish::message_type_traits::value_type::value>( args ); \ 105 | break; \ 106 | } \ 107 | } 108 | 109 | #endif //ROS_BABEL_FISH_MACROS_H 110 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/message_extractor.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_MESSAGE_EXTRACTOR_H 5 | #define ROS_BABEL_FISH_MESSAGE_EXTRACTOR_H 6 | 7 | #include "ros_babel_fish/exceptions/invalid_location_exception.h" 8 | #include "ros_babel_fish/babel_fish.h" 9 | #include "ros_babel_fish/babel_fish_message.h" 10 | 11 | namespace ros_babel_fish 12 | { 13 | 14 | namespace message_extraction 15 | { 16 | namespace MessageOffsetTypes 17 | { 18 | enum MessageOffsetType 19 | { 20 | Fixed, 21 | String, 22 | Array, 23 | ArrayElement // If pointing to specific array element, will check if array has enough elements 24 | }; 25 | } 26 | using MessageOffsetType = MessageOffsetTypes::MessageOffsetType; 27 | 28 | class MessageOffset 29 | { 30 | public: 31 | explicit MessageOffset( std::ptrdiff_t fixed_offset ) 32 | : type_( MessageOffsetTypes::Fixed ), offset_( fixed_offset ), index_( 0 ) { } 33 | 34 | explicit MessageOffset( MessageOffsetType type, std::ptrdiff_t offset = 0, 35 | std::vector array_offsets = {}, uint32_t index = 0 ) 36 | : array_offsets_( std::move( array_offsets )), type_( type ), offset_( offset ), index_( index ) { } 37 | 38 | std::ptrdiff_t offset( const uint8_t *buffer, std::ptrdiff_t current_offset ) const; 39 | 40 | bool isFixed() const { return type_ == MessageOffsetTypes::Fixed; } 41 | 42 | std::ptrdiff_t fixedOffset() const { return offset_; } 43 | 44 | MessageOffsetType type() const { return type_; } 45 | 46 | private: 47 | std::vector array_offsets_; 48 | MessageOffsetType type_; 49 | std::ptrdiff_t offset_; 50 | uint32_t index_; 51 | }; 52 | } 53 | 54 | class SubMessageLocation 55 | { 56 | public: 57 | SubMessageLocation(); 58 | 59 | explicit SubMessageLocation( std::string root_type, MessageTemplate::ConstPtr msg_template, 60 | std::vector offsets ); 61 | 62 | std::ptrdiff_t calculateOffset( const IBabelFishMessage &msg ) const; 63 | 64 | const MessageTemplate::ConstPtr &messageTemplate() const { return msg_template_; } 65 | 66 | bool isValid() const { return msg_template_ != nullptr; } 67 | 68 | /*! 69 | * @return The type for which the sub-message location is valid. 70 | */ 71 | const std::string &rootType() const { return root_type_; } 72 | 73 | private: 74 | std::vector offsets_; 75 | MessageTemplate::ConstPtr msg_template_; 76 | std::string root_type_; 77 | }; 78 | 79 | class MessageExtractor 80 | { 81 | public: 82 | explicit MessageExtractor( BabelFish &babel_fish ); 83 | 84 | /*! 85 | * Finds the location of the sub message accessed by the given path. 86 | * If you have, for example, a PoseStamped message and are only interested in the positon which you would normally 87 | * in a translated message as @code message["pose"]["position"] @endcode 88 | * You can extract the location of the position and subsequently use the extractor to only evaluate that message. 89 | * 90 | * @param path The path to the submessage, e.g., ".pose.position". The first dot is optional. 91 | * @return An object that can be evaluated to obtain the location of the submessage 92 | */ 93 | SubMessageLocation retrieveLocationForPath( const MessageTemplate::ConstPtr &msg_template, const std::string &path ); 94 | 95 | SubMessageLocation retrieveLocationForPath( const std::string &base_msg, const std::string &path ); 96 | 97 | SubMessageLocation retrieveLocationForPath( const IBabelFishMessage &msg, const std::string &path ); 98 | 99 | TranslatedMessage::Ptr extractMessage( const IBabelFishMessage::ConstPtr &msg, const SubMessageLocation &location ); 100 | 101 | Message::Ptr extractMessage( const IBabelFishMessage &msg, const SubMessageLocation &location ); 102 | 103 | template 104 | T extractValue( const IBabelFishMessage &msg, const SubMessageLocation &location ) 105 | { 106 | if ( msg.dataType() != location.rootType()) 107 | throw InvalidLocationException( "Message is of type '" + msg.dataType() + 108 | "' but location is for messages of type '" + location.rootType() + "'!" ); 109 | if ( message_type_traits::message_type::value != location.messageTemplate()->type ) 110 | throw BabelFishException( "Tried to extract incompatible type from '" + msg.dataType() + "' message!" ); 111 | std::ptrdiff_t offset = location.calculateOffset( msg ); 112 | if ( offset == -1 ) throw BabelFishException( "Failed to locate submessage in '" + msg.dataType() + "' message!" ); 113 | return *reinterpret_cast(msg.buffer() + offset); 114 | } 115 | 116 | template 117 | T extractValue( const IBabelFishMessage::ConstPtr &msg, const SubMessageLocation &location ) 118 | { 119 | return extractValue( *msg, location ); 120 | } 121 | 122 | private: 123 | BabelFish fish_; 124 | }; 125 | 126 | template<> 127 | std::string MessageExtractor::extractValue( const IBabelFishMessage &msg, const SubMessageLocation &location ); 128 | 129 | template<> 130 | ros::Time MessageExtractor::extractValue( const IBabelFishMessage &msg, const SubMessageLocation &location ); 131 | 132 | template<> 133 | ros::Duration MessageExtractor::extractValue( const IBabelFishMessage &msg, const SubMessageLocation &location ); 134 | } // ros_babel_fish 135 | 136 | #endif //ROS_BABEL_FISH_MESSAGE_EXTRACTOR_H 137 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/troll_node.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | /*! 11 | * The following example demonstrates how this library can be used to receive messages on one topic, modify elements 12 | * of the message and republish them on a different topic. 13 | * In this particular example, the incoming message is searched for string fields and their value is replaced with the 14 | * lyrics of Rick Astley's Never Gonna Give You Up. 15 | */ 16 | 17 | using namespace ros_babel_fish; 18 | 19 | void updateMessage( Message &message ); 20 | 21 | int main( int argc, char **argv ) 22 | { 23 | if ( argc != 3 ) 24 | { 25 | std::cout << "Invalid argument!" << std::endl; 26 | std::cout << "Usage: troll_node [INPUT TOPIC] [OUTPUT_TOPIC]" << std::endl; 27 | return 1; 28 | } 29 | 30 | ros::init( argc, argv, "ros_babel_fish_publish_string" ); 31 | ros::NodeHandle nh; 32 | std::string in_topic = argv[1]; 33 | std::string out_topic = argv[2]; 34 | ros::Publisher pub; 35 | bool first_message = true; 36 | BabelFish fish; 37 | 38 | ros::Subscriber sub = nh.subscribe( in_topic, 1, [ & ]( const BabelFishMessage::ConstPtr &msg ) 39 | { 40 | if ( first_message ) 41 | { 42 | pub = fish.advertise( nh, msg->dataType(), out_topic, 10 ); 43 | first_message = false; 44 | } 45 | TranslatedMessage::Ptr translated = fish.translateMessage( msg ); 46 | updateMessage( *translated->translated_message ); 47 | BabelFishMessage::Ptr result = fish.translateMessage( translated->translated_message ); 48 | pub.publish( result ); 49 | } ); 50 | 51 | ros::spin(); 52 | } 53 | 54 | static constexpr int song_text_length = 56; 55 | //! The lyrics of Rick Astley's masterpiece "Never Gonna Give You Up" (written and produced by Stock Aitken Waterman) 56 | std::string song_text[song_text_length] = { 57 | "We're no strangers to love", 58 | "You know the rules and so do I", 59 | "A full commitment's what I'm thinking of", 60 | "You wouldn't get this from any other guy", 61 | "I just wanna tell you how I'm feeling", 62 | "Gotta make you understand", 63 | "Never gonna give you up", 64 | "Never gonna let you down", 65 | "Never gonna run around and desert you", 66 | "Never gonna make you cry", 67 | "Never gonna say goodbye", 68 | "Never gonna tell a lie and hurt you", 69 | "We've known each other for so long", 70 | "Your heart's been aching but you're too shy to say it", 71 | "Inside we both know what's been going on", 72 | "We know the game and we're gonna play it", 73 | "And if you ask me how I'm feeling", 74 | "Don't tell me you're too blind to see", 75 | "Never gonna give you up", 76 | "Never gonna let you down", 77 | "Never gonna run around and desert you", 78 | "Never gonna make you cry", 79 | "Never gonna say goodbye", 80 | "Never gonna tell a lie and hurt you", 81 | "Never gonna give you up", 82 | "Never gonna let you down", 83 | "Never gonna run around and desert you", 84 | "Never gonna make you cry", 85 | "Never gonna say goodbye", 86 | "Never gonna tell a lie and hurt you", 87 | "Never gonna give, never gonna give", 88 | "(Give you up)", 89 | "(Ooh) Never gonna give, never gonna give", 90 | "(Give you up)", 91 | "We've known each other for so long", 92 | "Your heart's been aching but you're too shy to say it", 93 | "Inside we both know what's been going on", 94 | "We know the game and we're gonna play it", 95 | "I just wanna tell you how I'm feeling", 96 | "Gotta make you understand", 97 | "Never gonna give you up", 98 | "Never gonna let you down", 99 | "Never gonna run around and desert you", 100 | "Never gonna make you cry", 101 | "Never gonna say goodbye", 102 | "Never gonna tell a lie and hurt you", 103 | "Never gonna give you up", 104 | "Never gonna let you down", 105 | "Never gonna run around and desert you", 106 | "Never gonna make you cry", 107 | "Never gonna say goodbye", 108 | "Never gonna tell a lie and hurt you", 109 | "Never gonna give you up", 110 | "Never gonna let you down", 111 | "Never gonna run around and desert you", 112 | "Never gonna make you cry", 113 | }; 114 | 115 | int song_text_index = 0; 116 | 117 | void updateMessage( Message &message ) 118 | { 119 | if ( message.type() == MessageTypes::String ) 120 | { 121 | message = song_text[song_text_index]; 122 | ++song_text_index; 123 | if ( song_text_index >= song_text_length ) song_text_index = 0; 124 | } 125 | else if ( message.type() == MessageTypes::Array ) 126 | { 127 | if ( message.as().elementType() == MessageTypes::Compound ) 128 | { 129 | auto &array = message.as>(); 130 | for ( size_t i = 0; i < array.length(); ++i ) 131 | { 132 | updateMessage( array[i] ); 133 | } 134 | } 135 | else if ( message.as().elementType() == MessageTypes::String ) 136 | { 137 | auto &array = message.as>(); 138 | for ( size_t i = 0; i < array.length(); ++i ) 139 | { 140 | array.assign( i, song_text[song_text_index] ); 141 | ++song_text_index; 142 | if ( song_text_index >= song_text_length ) song_text_index = 0; 143 | } 144 | } 145 | } 146 | else if ( message.type() == MessageTypes::Compound ) 147 | { 148 | auto &compound = message.as(); 149 | for ( Message *child : compound.values()) 150 | { 151 | updateMessage( *child ); 152 | } 153 | } 154 | } 155 | -------------------------------------------------------------------------------- /ros_babel_fish/src/messages/value_message.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "ros_babel_fish/messages/value_message.h" 5 | 6 | namespace ros_babel_fish 7 | { 8 | 9 | //! ============== Bool Specialization ============== 10 | 11 | template<> 12 | bool ValueMessage::getValue() const 13 | { 14 | if ( from_stream_ ) 15 | { 16 | return *reinterpret_cast(stream_) != 0; 17 | } 18 | return value_; 19 | } 20 | 21 | template<> 22 | size_t ValueMessage::_sizeInBytes() const { return 1; } 23 | 24 | template<> 25 | ValueMessage *ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, size_t &bytes_read ) 26 | { 27 | (void) stream_length; // For unused warning 28 | uint8_t val = *reinterpret_cast(stream + bytes_read); 29 | ++bytes_read; 30 | if ( bytes_read > stream_length ) 31 | throw BabelFishException( "Unexpected end of stream while reading message from stream!" ); 32 | return new ValueMessage( val != 0 ); 33 | } 34 | 35 | template<> 36 | size_t ValueMessage::writeToStream( uint8_t *stream ) const 37 | { 38 | if ( from_stream_ ) 39 | { 40 | *stream = *stream_; 41 | return 1; 42 | } 43 | *stream = static_cast(value_ ? 1 : 0); 44 | return 1; 45 | } 46 | 47 | //! ============== Time Specialization ============== 48 | 49 | template<> 50 | ros::Time ValueMessage::getValue() const 51 | { 52 | if ( from_stream_ ) 53 | { 54 | uint32_t secs = *reinterpret_cast(stream_); 55 | uint32_t nsecs = *reinterpret_cast(stream_ + 4); 56 | return { secs, nsecs }; 57 | } 58 | return value_; 59 | } 60 | 61 | template<> 62 | size_t ValueMessage::_sizeInBytes() const { return 8; } 63 | 64 | 65 | template<> 66 | ValueMessage *ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, 67 | size_t &bytes_read ) 68 | { 69 | (void) stream_length; // For unused warning 70 | uint32_t secs = *reinterpret_cast(stream + bytes_read); 71 | uint32_t nsecs = *reinterpret_cast(stream + bytes_read + 4); 72 | bytes_read += 8; 73 | if ( bytes_read > stream_length ) 74 | throw BabelFishException( "Unexpected end of stream while reading message from stream!" ); 75 | return new ValueMessage( ros::Time( secs, nsecs )); 76 | } 77 | 78 | template<> 79 | size_t ValueMessage::writeToStream( uint8_t *stream ) const 80 | { 81 | if ( from_stream_ ) 82 | { 83 | std::memcpy( stream, stream_, 8 ); 84 | return 8; 85 | } 86 | *reinterpret_cast(stream) = value_.sec; 87 | *reinterpret_cast(stream + 4) = value_.nsec; 88 | return 8; 89 | } 90 | 91 | //! ============== Duration Specialization ============== 92 | 93 | template<> 94 | ros::Duration ValueMessage::getValue() const 95 | { 96 | if ( from_stream_ ) 97 | { 98 | int32_t secs = *reinterpret_cast(stream_); 99 | int32_t nsecs = *reinterpret_cast(stream_ + sizeof( int32_t )); 100 | return { secs, nsecs }; 101 | } 102 | return value_; 103 | } 104 | 105 | template<> 106 | size_t ValueMessage::_sizeInBytes() const { return 8; } 107 | 108 | 109 | template<> 110 | ValueMessage *ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, 111 | size_t &bytes_read ) 112 | { 113 | (void) stream_length; // For unused warning 114 | int32_t secs = *reinterpret_cast(stream + bytes_read); 115 | int32_t nsecs = *reinterpret_cast(stream + bytes_read + sizeof( int32_t )); 116 | bytes_read += 8; 117 | if ( bytes_read > stream_length ) 118 | throw BabelFishException( "Unexpected end of stream while reading message from stream!" ); 119 | return new ValueMessage( ros::Duration( secs, nsecs )); 120 | } 121 | 122 | template<> 123 | size_t ValueMessage::writeToStream( uint8_t *stream ) const 124 | { 125 | if ( from_stream_ ) 126 | { 127 | std::memcpy( stream, stream_, 8 ); 128 | return 8; 129 | } 130 | *reinterpret_cast(stream) = value_.sec; 131 | *reinterpret_cast(stream + sizeof( int32_t )) = value_.nsec; 132 | return 8; 133 | } 134 | 135 | //! ============== String Specialization ============== 136 | 137 | template<> 138 | std::string ValueMessage::getValue() const 139 | { 140 | // Lazy copy only if needed but in the stream the string is not 0 terminated 141 | if ( from_stream_ ) 142 | { 143 | uint32_t len = *reinterpret_cast(stream_); 144 | return std::string( reinterpret_cast(stream_ + 4), len ); 145 | } 146 | return value_; 147 | } 148 | 149 | template<> 150 | size_t ValueMessage::_sizeInBytes() const 151 | { 152 | if ( from_stream_ ) return *reinterpret_cast(stream_) + 4; 153 | return value_.length() + 4; 154 | } 155 | 156 | template<> 157 | ValueMessage *ValueMessage::fromStream( const uint8_t *stream, size_t stream_length, 158 | size_t &bytes_read ) 159 | { 160 | (void) stream_length; // For unused warning 161 | const uint8_t *begin = stream + bytes_read; 162 | uint32_t len = *reinterpret_cast( begin ); 163 | bytes_read += len + sizeof( uint32_t ); 164 | if ( bytes_read > stream_length ) 165 | throw BabelFishException( "Unexpected end of stream while reading message from stream!" ); 166 | return new ValueMessage( begin ); 167 | } 168 | 169 | template<> 170 | size_t ValueMessage::writeToStream( uint8_t *stream ) const 171 | { 172 | if ( from_stream_ ) 173 | { 174 | uint32_t len = *reinterpret_cast(stream_) + sizeof( uint32_t ); 175 | std::memcpy( stream, stream_, len ); 176 | return len; 177 | } 178 | *reinterpret_cast(stream) = value_.length(); 179 | stream += sizeof( uint32_t ); 180 | memcpy( stream, value_.data(), value_.length()); 181 | return value_.length() + sizeof( uint32_t ); 182 | } 183 | } 184 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | [![Build Status](https://app.travis-ci.com/StefanFabian/ros_babel_fish.svg?branch=kinetic)](https://app.travis-ci.com/StefanFabian/ros_babel_fish) 2 | [![codecov](https://codecov.io/gh/StefanFabian/ros_babel_fish/branch/master/graph/badge.svg)](https://codecov.io/gh/StefanFabian/ros_babel_fish) 3 | 4 | ## Scientific Works 5 | If you are using this module in a scientific context, feel free to cite this paper: 6 | ``` 7 | @INPROCEEDINGS{fabian2021hri, 8 | author = {Stefan Fabian and Oskar von Stryk}, 9 | title = {Open-Source Tools for Efficient ROS and ROS2-based 2D Human-Robot Interface Development}, 10 | year = {2021}, 11 | booktitle = {2021 European Conference on Mobile Robots (ECMR)}, 12 | } 13 | ``` 14 | 15 | ## ROS BabelFish 16 | This library enables ROS nodes written in C++ to communicate using message types that are unknown at compile time. 17 | 18 | > [!IMPORTANT] 19 | > The ROS2 version was moved and can be found [here](https://github.com/LOEWE-emergenCITY/ros_babel_fish). 20 | 21 | You can subscribe and even publish any available message type. 22 | It also supports both providing and calling a service. 23 | 24 | Please strongly consider whether you actually need this library because there may be a better solution. 25 | Possible use cases where you do need it are: 26 | * UIs displaying the content of various at compile time unknown messages 27 | * Plugins for (script) languages that can not access the C++ message definitions without modification 28 | * Spot for shameless self-advertising: Check out my [ROS QML plugin](https://github.com/StefanFabian/qml_ros_plugin) which uses this library to allow subscribing, publishing and more directly in QML 29 | 30 | The main focus of this library was usability but it is also very performant since it uses a lazy copy mechanism for bigger fields such as big arrays. 31 | Instead of copying the message it will retain a pointer at the start of the field. A copy is only made if explicitly requested or a value in the 32 | field is changed. 33 | 34 | ## Examples 35 | ### Subscribing 36 | ```C++ 37 | NodeHandle nh; 38 | BabelFish fish; 39 | // Subscribe topic /pose 40 | ros::Subscriber sub = nh.subscribe( topic, 1, &callback ); 41 | 42 | /* ... */ 43 | 44 | void callback( const ros_babel_fish::BabelFishMessage::ConstPtr &msg ) 45 | { 46 | std::cout << "Message received!" << std::endl; 47 | std::cout << "Data Type:" << msg->dataType() << std::endl; // geometry_msgs/Pose 48 | std::cout << "MD5:" << msg->md5Sum() << std::endl; // e45d45a5a1ce597b249e23fb30fc871f 49 | std::cout << "Message Definition:" << std::endl; 50 | std::cout << msg->definition() << std::endl; 51 | std::cout << "Message Content:" << std::endl; 52 | TranslatedMessage::Ptr translated = fish->translateMessage( msg ); 53 | auto &compound = translated->translated_message->as(); 54 | std::cout << "Position: " << compound["position"]["x"].value() << ", " << compound["position"]["y"].value() << ", " 55 | << compound["position"]["z"].value() << std::endl; 56 | std::cout << "Orientation: " << compound["orientation"]["w"].value() << ", " << compound["orientation"]["x"].value() << ", " 57 | << compound["orientation"]["y"].value() << ", " << compound["orientation"]["z"].value() << std::endl; 58 | }; 59 | ``` 60 | 61 | ### Publishing 62 | ```C++ 63 | NodeHandle nh; 64 | BabelFish fish; 65 | // Advertise a publisher on topic /pose 66 | ros::Publisher pub_pose = fish.advertise( nh, "geometry_msgs/Pose", "/pose", 1, true ); 67 | 68 | Message::Ptr message = fish.createMessage( "geometry_msgs/Pose" ); 69 | auto &compound = message->as(); 70 | compound["position"].as()["x"].as>().setValue(1.1); 71 | // or using convenience methods 72 | compound["position"]["y"].as>().setValue(2.4); 73 | // or using even more convenience methods 74 | compound["position"]["z"] = 3.6; 75 | // Be careful with your types here. Casting to a wrong type will throw an exception! 76 | // The as> method is also a bit faster because the convenience method 77 | // will automatically convert to the right type and perform bound and compatibility checks. 78 | // This makes it more robust but comes with a little overhead. 79 | // Note that assigning a double to a float field will always throw an exception because 80 | // the float may not have the required resolution. 81 | // Assigning, e.g., an int to a uint8 field will only throw if the int is out of bounds (0-255) 82 | // otherwise a warning will be printed because uint8 is not compatible with all possible values 83 | // of int. This warning can be disabled as a compile option. 84 | 85 | compound["orientation"]["w"] = 0.384; 86 | compound["orientation"]["x"] = -0.003; 87 | compound["orientation"]["y"] = -0.876; 88 | compound["orientation"]["z"] = 0.292; 89 | 90 | BabelFishMessage::Ptr translated_message = fish.translateMessage( message ); 91 | pub_pose.publish( translated_message ); 92 | ``` 93 | 94 | ### Message Extraction 95 | If you are only interested in a specific part of the message, you may not want to deserialize the entire message. 96 | ```C++ 97 | BabelFish fish; 98 | MessageExtractor extractor(fish); 99 | // We want the position of a pose stamped 100 | SubMessageLocation location = extractor.retrieveLocationForPath( "geometry_msgs/PoseStamped", "pose.position" ); 101 | BabelFishMessage::ConstPtr msg = ros::topic::waitForMessage( "/topic" ); 102 | TranslatedMessage::Ptr translated = extractor.extractMessage( msg, location ); 103 | auto &compound = translated->translated_message->as(); 104 | std::cout << "Position: " << compound["x"].value() << ", " << compound["y"].value() << ", " 105 | << compound["z"].value() << std::endl; 106 | 107 | // You can also extract primitives (but you need to make sure you extract the right type or the extractor will throw!) 108 | SubMessageLocation location_of_x = extractor.retrieveLocationForPath( "geometry_msgs/PoseStamped", "pose.position.x" ); 109 | std::cout << "Position X: " << extractor.extractValue( msg, location_of_x ) << std::endl; 110 | ``` 111 | 112 | For more in-depth examples and examples regarding service or action calls check the example folder. 113 | 114 | 115 | ## Benchmarks 116 | Check the separate [ros_babel_fish_benchmarks repo](https://github.com/StefanFabian/ros_babel_fish_benchmarks) for benchmarks. 117 | 118 | ## Current TODOs 119 | 120 | - [ ] Creating a reusable service client with at compile time unknown service definition 121 | - [ ] Documentation 122 | - [ ] Providing an action server(?) 123 | -------------------------------------------------------------------------------- /ros_babel_fish/test/common.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 17.09.19. 3 | // 4 | 5 | #ifndef ROS_BABEL_FISH_TEST_COMMON_H 6 | #define ROS_BABEL_FISH_TEST_COMMON_H 7 | 8 | #include 9 | 10 | #include 11 | #include 12 | 13 | template 14 | void fillArray( std::vector &msg, unsigned seed ) 15 | { 16 | std::default_random_engine generator( seed ); 17 | typedef typename std::conditional::value, std::uniform_real_distribution, std::uniform_int_distribution>::type Distribution; 18 | Distribution distribution( std::numeric_limits::min(), std::numeric_limits::max()); 19 | std::uniform_int_distribution length_distribution( 10, 1000 ); 20 | size_t length = length_distribution( generator ); 21 | msg.reserve( length ); 22 | for ( size_t i = 0; i < length; ++i ) 23 | { 24 | msg.push_back( distribution( generator )); 25 | } 26 | } 27 | 28 | template<> 29 | void fillArray( std::vector &msg, unsigned seed ) 30 | { 31 | std::default_random_engine generator( seed ); 32 | std::uniform_int_distribution distribution( 0, 1 ); 33 | std::uniform_int_distribution length_distribution( 10, 1000 ); 34 | size_t length = length_distribution( generator ); 35 | msg.reserve( length ); 36 | for ( size_t i = 0; i < length; ++i ) 37 | { 38 | msg.push_back( distribution( generator ) == 1 ); 39 | } 40 | } 41 | 42 | template 43 | void fillArray( boost::array &msg, unsigned seed ) 44 | { 45 | std::default_random_engine generator( seed ); 46 | typedef typename std::conditional::value, std::uniform_real_distribution, std::uniform_int_distribution>::type Distribution; 47 | Distribution distribution( std::numeric_limits::min(), std::numeric_limits::max()); 48 | for ( size_t i = 0; i < L; ++i ) 49 | { 50 | msg.at( i ) = distribution( generator ); 51 | } 52 | } 53 | 54 | template<> 55 | void fillArray( std::vector &msg, unsigned seed ) 56 | { 57 | std::default_random_engine generator( seed ); 58 | std::uniform_real_distribution distribution( 0, 1E9 ); 59 | std::uniform_int_distribution length_distribution( 10, 1000 ); 60 | size_t length = length_distribution( generator ); 61 | msg.reserve( length ); 62 | for ( size_t i = 0; i < length; ++i ) 63 | { 64 | msg.emplace_back( distribution( generator )); 65 | } 66 | } 67 | 68 | template 69 | void fillArray( boost::array &msg, unsigned seed ) 70 | { 71 | std::default_random_engine generator( seed ); 72 | std::uniform_real_distribution distribution( 0, 1E9 ); 73 | for ( size_t i = 0; i < L; ++i ) 74 | { 75 | msg.at( i ) = ros::Time( distribution( generator )); 76 | } 77 | } 78 | 79 | template<> 80 | void fillArray( std::vector &msg, unsigned seed ) 81 | { 82 | std::default_random_engine generator( seed ); 83 | std::uniform_real_distribution distribution( -1E9, 1E9 ); 84 | std::uniform_int_distribution length_distribution( 10, 1000 ); 85 | size_t length = length_distribution( generator ); 86 | msg.reserve( length ); 87 | for ( size_t i = 0; i < length; ++i ) 88 | { 89 | msg.emplace_back( distribution( generator )); 90 | } 91 | } 92 | 93 | template 94 | void fillArray( boost::array &msg, unsigned seed ) 95 | { 96 | std::default_random_engine generator( seed ); 97 | std::uniform_real_distribution distribution( -1E9, 1E9 ); 98 | for ( size_t i = 0; i < L; ++i ) 99 | { 100 | msg.at( i ) = ros::Duration( distribution( generator )); 101 | } 102 | } 103 | 104 | std::string randomString( unsigned seed, int length = -1 ) 105 | { 106 | std::default_random_engine generator( seed ); 107 | static const char alphanum[] = 108 | "0123456789" 109 | "ABCDEFGHIJKLMNOPQRSTUVWXYZ" 110 | "abcdefghijklmnopqrstuvwxyz"; 111 | std::uniform_int_distribution distribution( 0, sizeof( alphanum ) - 2 ); 112 | if ( length == -1 ) 113 | { 114 | std::uniform_int_distribution length_distribution( 1, 1000 ); 115 | length = length_distribution( generator ); 116 | } 117 | char result[length + 1]; 118 | for ( int i = 0; i < length; ++i ) 119 | { 120 | result[i] = alphanum[distribution( generator )]; 121 | } 122 | result[length] = 0; 123 | return std::string( result ); 124 | } 125 | 126 | template<> 127 | void fillArray( std::vector &msg, unsigned seed ) 128 | { 129 | std::default_random_engine generator( seed ); 130 | std::uniform_int_distribution distribution( std::numeric_limits::min()); 131 | std::uniform_int_distribution length_distribution( 10, 1000 ); 132 | size_t length = length_distribution( generator ); 133 | msg.reserve( length ); 134 | for ( size_t i = 0; i < length; ++i ) 135 | { 136 | msg.push_back( randomString( distribution( generator ), i == 0 ? 1 : -1 )); 137 | } 138 | } 139 | 140 | template 141 | void fillArray( boost::array &msg, unsigned seed ) 142 | { 143 | std::default_random_engine generator( seed ); 144 | std::uniform_int_distribution distribution( std::numeric_limits::min()); 145 | for ( size_t i = 0; i < msg.length(); ++i ) 146 | { 147 | msg.at( i ) = randomString( distribution( generator ), i == 0 ? 1 : -1 ); 148 | } 149 | } 150 | 151 | template<> 152 | void fillArray( std::vector &msg, 153 | unsigned seed ) 154 | { 155 | std::default_random_engine generator( seed ); 156 | std::uniform_int_distribution distribution( std::numeric_limits::min()); 157 | std::uniform_int_distribution length_distribution( 10, 1000 ); 158 | size_t length = length_distribution( generator ); 159 | msg.reserve( length ); 160 | for ( size_t i = 0; i < length; ++i ) 161 | { 162 | ros_babel_fish_test_msgs::TestSubArray message; 163 | fillArray( message.ints, seed++ ); 164 | fillArray( message.strings, seed++ ); 165 | fillArray( message.times, seed++ ); 166 | msg.push_back( message ); 167 | } 168 | } 169 | 170 | template 171 | void fillArray( boost::array &msg, 172 | unsigned seed ) 173 | { 174 | std::default_random_engine generator( seed ); 175 | std::uniform_int_distribution distribution( std::numeric_limits::min()); 176 | for ( size_t i = 0; i < L; ++i ) 177 | { 178 | fillArray( msg[i].ints, seed++ ); 179 | fillArray( msg[i].strings, seed++ ); 180 | fillArray( msg[i].times, seed++ ); 181 | } 182 | } 183 | 184 | #endif // ROS_BABEL_FISH_TEST_COMMON_H 185 | -------------------------------------------------------------------------------- /ros_babel_fish/test/message_extractor.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 17.09.19. 3 | // 4 | 5 | #include "common.h" 6 | #include "message_comparison.h" 7 | 8 | #include 9 | #include 10 | #include 11 | 12 | #include 13 | #include 14 | #include 15 | 16 | using namespace ros_babel_fish; 17 | 18 | TEST( MessageExtractorTest, calculateOffset ) 19 | { 20 | BabelFish fish; 21 | MessageExtractor extractor( fish ); 22 | EXPECT_THROW( extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", "..subarrays" ), 23 | InvalidMessagePathException ); 24 | { 25 | SubMessageLocation location; 26 | EXPECT_FALSE( location.isValid()); 27 | location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", "bools" ); 28 | EXPECT_TRUE( location.isValid()); 29 | EXPECT_EQ( location.calculateOffset( BabelFishMessage()), 0 ); 30 | ASSERT_EQ( location.messageTemplate()->type, MessageTypes::Array ); 31 | EXPECT_EQ( location.messageTemplate()->array.element_type, MessageTypes::Bool ); 32 | } 33 | { 34 | SubMessageLocation location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", ".bools" ); 35 | EXPECT_EQ( location.calculateOffset( BabelFishMessage()), 0 ); 36 | ASSERT_EQ( location.messageTemplate()->type, MessageTypes::Array ); 37 | EXPECT_EQ( location.messageTemplate()->array.element_type, MessageTypes::Bool ); 38 | } 39 | } 40 | 41 | TEST( MessageExtractorTest, extractValue ) 42 | { 43 | BabelFish fish; 44 | MessageExtractor extractor( fish ); 45 | ros_babel_fish_test_msgs::TestArray msg; 46 | unsigned SEED = 42; 47 | fillArray( msg.bools, SEED++ ); 48 | fillArray( msg.uint8s, SEED++ ); 49 | fillArray( msg.uint16s, SEED++ ); 50 | fillArray( msg.uint32s, SEED++ ); 51 | fillArray( msg.uint64s, SEED++ ); 52 | fillArray( msg.int8s, SEED++ ); 53 | fillArray( msg.int16s, SEED++ ); 54 | fillArray( msg.int32s, SEED++ ); 55 | fillArray( msg.int64s, SEED++ ); 56 | fillArray( msg.float32s, SEED++ ); 57 | fillArray( msg.float64s, SEED++ ); 58 | fillArray( msg.times, SEED++ ); 59 | fillArray( msg.durations, SEED++ ); 60 | fillArray( msg.strings, SEED++ ); 61 | fillArray( msg.subarrays_fixed, SEED++ ); 62 | fillArray( msg.subarrays, SEED++ ); 63 | EXPECT_THROW( 64 | extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", ".subarrays_fixed.4.times.42" ), 65 | InvalidMessagePathException ); 66 | EXPECT_THROW( 67 | extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", ".subarrays_fixed.4.timers.13" ), 68 | InvalidMessagePathException ); 69 | EXPECT_THROW( 70 | extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", ".subarrays_fixed.4.times.abc" ), 71 | InvalidMessagePathException ); 72 | SubMessageLocation location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", 73 | ".subarrays_fixed.4.times.13" ); 74 | 75 | msg.subarrays_fixed[4].times[13] = ros::Time( 13, 37 ); 76 | ros::SerializedMessage serialized_msg = ros::serialization::serializeMessage( msg ); 77 | BabelFishMessage bf_msg; 78 | bf_msg.morph( fish.descriptionProvider()->getMessageDescription( "ros_babel_fish_test_msgs/TestArray" )); 79 | ros::serialization::deserializeMessage( serialized_msg, bf_msg ); 80 | EXPECT_EQ( extractor.extractValue( bf_msg, location ), ros::Time( 13, 37 )); 81 | msg.subarrays_fixed[4].times[13] = ros::Time( 42, 96 ); 82 | size_t int_size = msg.int32s.size(); 83 | msg.int32s.emplace_back( 1 ); 84 | msg.int32s.emplace_back( 2 ); 85 | msg.strings.emplace_back( "Hopefully not the same as the random string :)" ); 86 | serialized_msg = ros::serialization::serializeMessage( msg ); 87 | ros::serialization::deserializeMessage( serialized_msg, bf_msg ); 88 | EXPECT_EQ( extractor.extractValue( bf_msg, location ), ros::Time( 42, 96 )); 89 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), BabelFishException ); 90 | location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", 91 | ".int32s." + std::to_string( int_size )); 92 | EXPECT_EQ( extractor.extractValue( bf_msg, location ), 1 ); 93 | location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", 94 | ".int32s." + std::to_string( int_size + 1 )); 95 | EXPECT_EQ( extractor.extractValue( bf_msg, location ), 2 ); 96 | location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", 97 | ".strings." + std::to_string( msg.strings.size() - 1 )); 98 | EXPECT_EQ( extractor.extractValue( bf_msg, location ), msg.strings[msg.strings.size() - 1] ); 99 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), BabelFishException ); 100 | location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestArray", ".durations.3" ); 101 | EXPECT_EQ( extractor.extractValue( bf_msg, location ), msg.durations[3] ); 102 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), BabelFishException ); 103 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), BabelFishException ); 104 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), BabelFishException ); 105 | 106 | MessageDescription::ConstPtr description = fish.descriptionProvider()->getMessageDescription( 107 | "ros_babel_fish_test_msgs/TestArray" ); 108 | location = extractor.retrieveLocationForPath( description->message_template, ".subarrays.4" ); 109 | { 110 | Message::Ptr translated = extractor.extractMessage( bf_msg, location ); 111 | EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( msg.subarrays[4], translated )); 112 | EXPECT_THROW( extractor.retrieveLocationForPath( description->message_template->compound.types[3], ".4" ), 113 | InvalidTemplateException ); 114 | } 115 | BabelFishMessage::Ptr bf_msg_ptr( new BabelFishMessage ); 116 | bf_msg_ptr->morph( fish.descriptionProvider()->getMessageDescription( "ros_babel_fish_test_msgs/TestArray" )); 117 | ros::serialization::deserializeMessage( serialized_msg, *bf_msg_ptr ); 118 | { 119 | TranslatedMessage::Ptr translated = extractor.extractMessage( bf_msg_ptr, location ); 120 | EXPECT_TRUE( MESSAGE_CONTENT_EQUAL( msg.subarrays[4], translated->translated_message )); 121 | } 122 | 123 | location = extractor.retrieveLocationForPath( "ros_babel_fish_test_msgs/TestSubArray", "times.4" ); 124 | EXPECT_TRUE( location.isValid()); 125 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), InvalidLocationException ); 126 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), InvalidLocationException ); 127 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), InvalidLocationException ); 128 | EXPECT_THROW( extractor.extractValue( bf_msg, location ), InvalidLocationException ); 129 | EXPECT_THROW( extractor.extractMessage( bf_msg, location ), InvalidLocationException ); 130 | EXPECT_THROW( extractor.extractMessage( bf_msg_ptr, location ), InvalidLocationException ); 131 | } 132 | 133 | int main( int argc, char **argv ) 134 | { 135 | testing::InitGoogleTest( &argc, argv ); 136 | ros::init( argc, argv, "test_message_lookup" ); 137 | ros::NodeHandle nh; 138 | return RUN_ALL_TESTS(); 139 | } 140 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/actionlib/babel_fish_action_result.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_ACTION_RESULT_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_ACTION_RESULT_H 6 | 7 | #include "ros_babel_fish/generation/providers/message_only_description_provider.h" 8 | 9 | namespace ros_babel_fish 10 | { 11 | 12 | template 13 | struct BabelFishActionResult_ 14 | { 15 | typedef BabelFishActionResult_ Type; 16 | 17 | BabelFishActionResult_() = default; 18 | 19 | explicit BabelFishActionResult_( const ContainerAllocator &allocator ) : header( allocator ), status( allocator ) { } 20 | 21 | const std::string &md5Sum() const { return md5_; } 22 | 23 | const std::string &dataType() const { return datatype_; } 24 | 25 | const std::string &definition() const { return definition_; } 26 | 27 | bool isLatched() const { return latched_; } 28 | 29 | void morph( const std::string &md5sum, const std::string &datatype, const std::string &definition, 30 | bool latched = false ) 31 | { 32 | md5_ = md5sum; 33 | datatype_ = datatype; 34 | definition_ = definition; 35 | latched_ = latched; 36 | 37 | MessageOnlyDescriptionProvider provider; 38 | MessageDescription::ConstPtr action_goal_description = provider.registerMessageByDefinition( datatype_, 39 | definition_ ); 40 | assert( action_goal_description != nullptr ); 41 | assert( action_goal_description->message_template != nullptr ); 42 | assert( action_goal_description->message_template->type == MessageTypes::Compound ); 43 | auto it = std::find( action_goal_description->message_template->compound.names.begin(), 44 | action_goal_description->message_template->compound.names.end(), "result" ); 45 | if ( it == action_goal_description->message_template->compound.names.end()) 46 | throw BabelFishException( "Did not find result in ActionResult message of type '" + datatype + "'!" ); 47 | int goal_index = std::distance( action_goal_description->message_template->compound.names.begin(), it ); 48 | MessageDescription::ConstPtr goal_description = provider.getMessageDescription( 49 | action_goal_description->message_template->compound.types[goal_index]->compound.datatype ); 50 | result.morph( goal_description ); 51 | } 52 | 53 | void morph( const MessageDescription::ConstPtr &description ) 54 | { 55 | morph( description->md5, description->datatype, description->message_definition ); 56 | } 57 | 58 | typedef ::std_msgs::Header_ _header_type; 59 | _header_type header; 60 | 61 | typedef ::actionlib_msgs::GoalStatus_ _status_type; 62 | _status_type status; 63 | 64 | typedef BabelFishMessage _result_type; 65 | _result_type result; 66 | 67 | typedef boost::shared_ptr > Ptr; 68 | typedef boost::shared_ptr > ConstPtr; 69 | private: 70 | std::string md5_; 71 | std::string datatype_; 72 | std::string definition_; 73 | bool latched_ = false; 74 | }; 75 | 76 | typedef BabelFishActionResult_ > BabelFishActionResult; 77 | typedef typename BabelFishActionGoal::Ptr BabelFishActionResultPtr; 78 | typedef typename BabelFishActionGoal::ConstPtr BabelFishActionResultConstPtr; 79 | } 80 | 81 | #ifndef DOXYGEN_SHOULD_SKIP_THIS 82 | 83 | // Message and service traits for serialization API 84 | namespace ros 85 | { 86 | namespace message_traits 87 | { 88 | 89 | template 90 | struct IsFixedSize<::ros_babel_fish::BabelFishActionResult_ > : FalseType 91 | { 92 | }; 93 | template 94 | struct IsFixedSize > : FalseType 95 | { 96 | }; 97 | 98 | template 99 | struct IsMessage<::ros_babel_fish::BabelFishActionResult_ > : TrueType 100 | { 101 | }; 102 | template 103 | struct IsMessage > : TrueType 104 | { 105 | }; 106 | 107 | template 108 | struct HasHeader<::ros_babel_fish::BabelFishActionResult_ > : TrueType 109 | { 110 | }; 111 | template 112 | struct HasHeader > : TrueType 113 | { 114 | }; 115 | 116 | template 117 | struct MD5Sum<::ros_babel_fish::BabelFishActionResult_ > 118 | { 119 | static const char * 120 | value( const ::ros_babel_fish::BabelFishActionResult_ &m ) { return m.md5Sum().c_str(); } 121 | 122 | // A BabelFishActionGoal can be of any type 123 | static const char *value() { return "*"; } 124 | }; 125 | 126 | template 127 | struct DataType<::ros_babel_fish::BabelFishActionResult_ > 128 | { 129 | static const char * 130 | value( const ::ros_babel_fish::BabelFishActionResult_ &m ) { return m.dataType().c_str(); } 131 | 132 | // A BabelFishActionGoal can be of any type 133 | static const char *value() { return "*"; } 134 | }; 135 | 136 | template 137 | struct Definition<::ros_babel_fish::BabelFishActionResult_ > 138 | { 139 | static const char * 140 | value( const ::ros_babel_fish::BabelFishActionResult_ &m ) { return m.definition().c_str(); } 141 | 142 | // A BabelFishActionGoal can be of any type 143 | static const char *value() { return "*"; } 144 | }; 145 | } // message_traits 146 | 147 | namespace serialization 148 | { 149 | 150 | template 151 | struct Serializer<::ros_babel_fish::BabelFishActionResult_ > 152 | { 153 | template 154 | inline static void write( Stream &stream, const ::ros_babel_fish::BabelFishActionResult_ &m ) 155 | { 156 | stream.next( m.header ); 157 | stream.next( m.status ); 158 | m.result.write( stream ); 159 | } 160 | 161 | template 162 | inline static void read( Stream &stream, ::ros_babel_fish::BabelFishActionResult_ &m ) 163 | { 164 | stream.next( m.header ); 165 | stream.next( m.status ); 166 | m.result.read( stream ); 167 | } 168 | 169 | inline static uint32_t serializedLength( const ::ros_babel_fish::BabelFishActionResult_ &m ) 170 | { 171 | LStream stream; 172 | stream.next( m.header ); 173 | stream.next( m.status ); 174 | return stream.getLength() + m.result.size(); 175 | } 176 | }; 177 | 178 | template 179 | struct PreDeserialize<::ros_babel_fish::BabelFishActionResult_ > 180 | { 181 | static void 182 | notify( const PreDeserializeParams<::ros_babel_fish::BabelFishActionResult_ > ¶ms ) 183 | { 184 | std::string md5 = (*params.connection_header)["md5sum"]; 185 | std::string datatype = (*params.connection_header)["type"]; 186 | std::string msg_def = (*params.connection_header)["message_definition"]; 187 | std::string latching = (*params.connection_header)["latching"]; 188 | 189 | params.message->morph( md5, datatype, msg_def, latching == "1" ); 190 | } 191 | }; 192 | } // serialization 193 | 194 | } // ros 195 | 196 | #endif // DOXYGEN_SHOULD_SKIP_THIS 197 | 198 | #endif //ROS_BABEL_FISH_BABEL_FISH_ACTION_RESULT_H 199 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/babel_fish.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_H 6 | 7 | #include "ros_babel_fish/generation/description_provider.h" 8 | #include "ros_babel_fish/generation/message_template.h" 9 | #include "ros_babel_fish/babel_fish_message.h" 10 | #include "ros_babel_fish/message_description.h" 11 | #include "ros_babel_fish/message_types.h" 12 | 13 | #include 14 | #include 15 | 16 | namespace ros_babel_fish 17 | { 18 | 19 | /*! 20 | * The Message internally points to the buffer of the BabelFishMessage, hence, this ensures that this buffer is not 21 | * destroyed as long as the message exists or it is detached from the buffer using Message::detachFromStream. 22 | */ 23 | struct TranslatedMessage 24 | { 25 | typedef std::shared_ptr Ptr; 26 | typedef std::shared_ptr ConstPtr; 27 | 28 | TranslatedMessage( IBabelFishMessage::ConstPtr input, Message::Ptr translated ) 29 | : input_message( std::move( input )), translated_message( std::move( translated )) { } 30 | 31 | IBabelFishMessage::ConstPtr input_message; 32 | Message::Ptr translated_message; 33 | }; 34 | 35 | /*! 36 | * Allows communication using message types that are not known at compile time. 37 | */ 38 | class BabelFish 39 | { 40 | public: 41 | /*! 42 | * Constructs an instance of BabelFish with a new instance of the default description provider. 43 | * If you have to use multiple BabelFish instances, it is recommended to shae the description provider to 44 | * prevent multiple look ups of the same message. 45 | */ 46 | BabelFish(); 47 | 48 | /*! 49 | * Constructs an instance of BabelFish with the given description provider. 50 | * @param description_provider The description provider to be used. 51 | * @throws BabelFishException If the passed description_provider is a nullptr. 52 | */ 53 | explicit BabelFish( DescriptionProvider::Ptr description_provider ); 54 | 55 | ~BabelFish(); 56 | 57 | /*! 58 | * Translates the given BabelFishMessage into a TranslatedMessage containing a reference to the input message and the 59 | * translated message. The reference to the input message is needed to ensure the data is not destroyed because 60 | * the translated message may depend on it. 61 | * @param msg The received BabelFishMessage 62 | * @return A struct containing the input and the translated message. 63 | */ 64 | TranslatedMessage::Ptr translateMessage( const IBabelFishMessage::ConstPtr &msg ); 65 | 66 | /*! 67 | * Translates the given BabelFishMessage into a translated message. 68 | * Since the passed BabelFishMessage is only passed as const reference, BabelFish can not make sure that it is 69 | * not destroyed during the lifetime of Message (or until Message is detached using Message::detachFromStream). 70 | * Hence, the user has to ensure the BabelFishMessage is not destroyed or detach the Message before it is destroyed. 71 | * @param msg The received BabelFishMessage 72 | * @return The translated message. 73 | */ 74 | Message::Ptr translateMessage( const IBabelFishMessage &msg ); 75 | 76 | /*! 77 | * Translates a message created by BabelFish into a BabelFishMessage that can be sent using the implementations 78 | * provided by ROS. 79 | * @param msg The input message 80 | * @return The serialized ROS compatible message 81 | */ 82 | BabelFishMessage::Ptr translateMessage( const Message::ConstPtr &msg ); 83 | 84 | /*! 85 | * @copydoc BabelFish::translateMessage(const Message::ConstPtr&) 86 | */ 87 | BabelFishMessage::Ptr translateMessage( const Message &msg ); 88 | 89 | /*! 90 | * @copydoc BabelFish::translateMessage(const Message::ConstPtr&) 91 | * @param latched This bool is passed to the headers 92 | */ 93 | BabelFishMessage::Ptr translateMessage( const Message &msg, bool latched ); 94 | 95 | /*! 96 | * @copydetails BabelFish::translateMessage(const Message::ConstPtr&) 97 | * @param msg The input message 98 | * @param result Container for the serialized ROS compatible message 99 | * @return True if successful, false otherwise 100 | */ 101 | bool translateMessage( const Message &msg, BabelFishMessage &result ); 102 | 103 | /*! 104 | * Advertises a publisher on the given topic. 105 | * @param nh The ros::NodeHandle used to advertise the topic 106 | * @param type The message type that is advertised, e.g.: "std_msgs/Header" 107 | * @param topic The topic to publish on 108 | * @param queue_size The maximum number of outgoing messages to be queued for delivery to subscribers 109 | * @param latch Whether or not this publisher should latch, i.e., always send out the last message to new subscribers 110 | * @param connect_cb Function to call whenever a subscriber connects to this topic 111 | * @param disconnect_cb Function to call whenever a subscriber disconnects from this topic 112 | * @return A ros::Publisher that can be used to publish BabelFishMessages filled with the given type on the given topic 113 | */ 114 | ros::Publisher advertise( ros::NodeHandle &nh, const std::string &type, const std::string &topic, 115 | uint32_t queue_size, bool latch = false, 116 | const ros::SubscriberStatusCallback &connect_cb = ros::SubscriberStatusCallback(), 117 | const ros::SubscriberStatusCallback &disconnect_cb = ros::SubscriberStatusCallback()); 118 | 119 | /*! 120 | * Advertises a service on the given topic. 121 | * @param nh The ros::NodeHandle used to advertise the service 122 | * @param type The service type that is advertised, e.g.: "rosapi/GetParam" 123 | * @param service The topic this service is advertised on 124 | * @param callback The callback to be executed for each service request 125 | * @return A ros::ServiceServer that can be used to provide a service of the given type on the given topic 126 | */ 127 | ros::ServiceServer advertiseService( ros::NodeHandle &nh, const std::string &type, const std::string &service, 128 | const std::function &callback ); 129 | 130 | /*! 131 | * Creates an empty message of the given type. 132 | * @param type The message type, e.g.: "std_msgs/Header" 133 | * @return An empty message of the given type 134 | * 135 | * @throws BabelFishException If the message description was not found 136 | */ 137 | Message::Ptr createMessage( const std::string &type ); 138 | 139 | /*! 140 | * Creates a service request message for the given service type. 141 | * @param type The type of the service, e.g., rosapi/GetParam 142 | * @return An empty service request message that can be used to call a service of the given type 143 | * 144 | * @throws BabelFishException If the service description was not found 145 | */ 146 | Message::Ptr createServiceRequest( const std::string &type ); 147 | 148 | /*! 149 | * Calls a service on the given topic with the given request 150 | * @param service 151 | * @param req 152 | * @param res 153 | * @return 154 | * 155 | * @throws BabelFishException If the passed req message is not a request 156 | * @throws BabelFishException If the service description was not found 157 | */ 158 | bool callService( const std::string &service, const Message::ConstPtr &req, TranslatedMessage::Ptr &res ); 159 | 160 | DescriptionProvider::Ptr &descriptionProvider(); 161 | 162 | private: 163 | DescriptionProvider::Ptr description_provider_; 164 | }; 165 | 166 | } // ros_babel_fish 167 | 168 | #endif //ROS_BABEL_FISH_BABEL_FISH_H 169 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/babel_fish_message.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_MESSAGE_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_MESSAGE_H 6 | 7 | #include "ros_babel_fish/message_description.h" 8 | 9 | #include 10 | #include 11 | #include 12 | 13 | namespace ros_babel_fish 14 | { 15 | 16 | /*! 17 | * A read-only interface for BabelFishMessage. 18 | */ 19 | class IBabelFishMessage 20 | { 21 | public: 22 | typedef boost::shared_ptr Ptr; 23 | typedef boost::shared_ptr ConstPtr; 24 | 25 | virtual ~IBabelFishMessage() = default; 26 | 27 | virtual const std::string &md5Sum() const = 0; 28 | 29 | virtual const std::string &dataType() const = 0; 30 | 31 | virtual const std::string &__getServerMD5Sum() const 32 | { 33 | static const std::string missing = "*"; 34 | return missing; 35 | } 36 | 37 | virtual const std::string &__getServiceDatatype() const 38 | { 39 | static const std::string missing = "*"; 40 | return missing; 41 | } 42 | 43 | virtual const std::string &definition() const = 0; 44 | 45 | virtual bool isLatched() const = 0; 46 | 47 | virtual uint32_t size() const = 0; 48 | 49 | virtual const uint8_t *buffer() const = 0; 50 | }; 51 | 52 | /*! 53 | * A message that can store any type of message. 54 | * The message contents can be retrieved by translating it with a BabelFish. 55 | */ 56 | class BabelFishMessage : public IBabelFishMessage 57 | { 58 | public: 59 | typedef boost::shared_ptr Ptr; 60 | typedef boost::shared_ptr ConstPtr; 61 | 62 | BabelFishMessage(); 63 | 64 | BabelFishMessage( const BabelFishMessage &other ); 65 | 66 | BabelFishMessage &operator=( const BabelFishMessage &other ); 67 | 68 | ~BabelFishMessage() override; 69 | 70 | const std::string &md5Sum() const final; 71 | 72 | const std::string &dataType() const final; 73 | 74 | const std::string &__getServerMD5Sum() const final; 75 | 76 | const std::string &__getServiceDatatype() const final; 77 | 78 | const std::string &definition() const final; 79 | 80 | bool isLatched() const final; 81 | 82 | void morph( const std::string &md5sum, const std::string &datatype, const std::string &definition, 83 | bool latched = false, const std::string &server_md5sum = "*" ); 84 | 85 | void morph( const MessageDescription::ConstPtr &description, const std::string &server_md5sum = "*" ); 86 | 87 | /*! 88 | * Writes the serialized message to the given stream. 89 | * @tparam Stream A stream class providing an advance method that takes a uint32_t with the size and returns the 90 | * pointer to a memory position that is big enough for the given amount of bytes 91 | * @param stream The stream the serialized message is written to 92 | */ 93 | template 94 | void write( Stream &stream ) const 95 | { 96 | if ( buffer_used_ > 0 ) 97 | std::memcpy( stream.advance( buffer_used_ ), buffer_, buffer_used_ ); 98 | } 99 | 100 | /*! 101 | * Reads a serialized message from a stream. 102 | * @tparam Stream A stream class providing a getData() method that returns a pointer to the data and a getLength() 103 | * method that returns the size of the data in bytes. 104 | * @param stream The stream from which the serialized message is read. 105 | */ 106 | template 107 | void read( Stream &stream ) 108 | { 109 | // Allocate buffer and copy data 110 | allocate( stream.getLength()); 111 | std::memcpy( buffer_, stream.getData(), stream.getLength()); 112 | } 113 | 114 | /*! 115 | * @return The size of the message which is the number of used bytes. 116 | */ 117 | uint32_t size() const final; 118 | 119 | uint8_t *buffer() { return buffer_; } 120 | 121 | const uint8_t *buffer() const final { return buffer_; } 122 | 123 | void allocate( size_t size ); 124 | 125 | private: 126 | std::string md5_; 127 | std::string server_md5_; 128 | std::string datatype_; 129 | mutable std::string service_datatype_; // Generated on-demand 130 | std::string definition_; 131 | bool latched_; 132 | 133 | uint8_t *buffer_; 134 | uint32_t buffer_size_; 135 | uint32_t buffer_used_; 136 | }; 137 | 138 | class BabelFishMessageException : public BabelFishException 139 | { 140 | public: 141 | explicit BabelFishMessageException( const std::string &msg ) : BabelFishException( msg ) { } 142 | }; 143 | } // ros_babel_fish 144 | 145 | // Message and service traits for serialization API 146 | namespace ros 147 | { 148 | namespace message_traits 149 | { 150 | 151 | template<> 152 | struct IsMessage<::ros_babel_fish::BabelFishMessage> : TrueType 153 | { 154 | }; 155 | template<> 156 | struct IsMessage : TrueType 157 | { 158 | }; 159 | 160 | template<> 161 | struct MD5Sum<::ros_babel_fish::BabelFishMessage> 162 | { 163 | static const char *value( const ::ros_babel_fish::BabelFishMessage &m ) { return m.__getServerMD5Sum().c_str(); } 164 | 165 | // A BabelFishMessage can be of any type 166 | static const char *value() { return "*"; } 167 | }; 168 | 169 | template<> 170 | struct DataType<::ros_babel_fish::BabelFishMessage> 171 | { 172 | static const char *value( const ::ros_babel_fish::BabelFishMessage &m ) { return m.dataType().c_str(); } 173 | 174 | // A BabelFishMessage can be of any type 175 | static const char *value() { return "*"; } 176 | }; 177 | 178 | template<> 179 | struct Definition<::ros_babel_fish::BabelFishMessage> 180 | { 181 | static const char *value( const ::ros_babel_fish::BabelFishMessage &m ) { return m.definition().c_str(); } 182 | }; 183 | } // message_traits 184 | 185 | namespace service_traits 186 | { 187 | template<> 188 | struct MD5Sum<::ros_babel_fish::BabelFishMessage> 189 | { 190 | static const char *value( const ::ros_babel_fish::BabelFishMessage &m ) { return m.__getServerMD5Sum().c_str(); } 191 | 192 | static const char *value() { return "*"; } 193 | }; 194 | 195 | template<> 196 | struct DataType<::ros_babel_fish::BabelFishMessage> 197 | { 198 | static const char *value( const ::ros_babel_fish::BabelFishMessage &m ) { return m.__getServiceDatatype().c_str(); } 199 | 200 | static const char *value() { return "*"; } 201 | }; 202 | } // service_traits 203 | 204 | 205 | namespace serialization 206 | { 207 | 208 | template<> 209 | struct Serializer<::ros_babel_fish::BabelFishMessage> 210 | { 211 | template 212 | inline static void write( Stream &stream, const ::ros_babel_fish::BabelFishMessage &m ) 213 | { 214 | m.write( stream ); 215 | } 216 | 217 | template 218 | inline static void read( Stream &stream, ::ros_babel_fish::BabelFishMessage &m ) 219 | { 220 | m.read( stream ); 221 | } 222 | 223 | inline static uint32_t serializedLength( const ::ros_babel_fish::BabelFishMessage &m ) 224 | { 225 | return m.size(); 226 | } 227 | }; 228 | 229 | 230 | template<> 231 | struct PreDeserialize<::ros_babel_fish::BabelFishMessage> 232 | { 233 | static void notify( const PreDeserializeParams<::ros_babel_fish::BabelFishMessage> ¶ms ) 234 | { 235 | std::string md5 = (*params.connection_header)["md5sum"]; 236 | std::string datatype = (*params.connection_header)["type"]; 237 | std::string msg_def = (*params.connection_header)["message_definition"]; 238 | std::string latching = (*params.connection_header)["latching"]; 239 | 240 | params.message->morph( md5, datatype, msg_def, latching == "1" ); 241 | } 242 | }; 243 | } // serialization 244 | 245 | } // ros 246 | 247 | #endif //ROS_BABEL_FISH_BABEL_FISH_MESSAGE_H 248 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/actionlib/babel_fish_action_feedback.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_ACTION_FEEDBACK_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_ACTION_FEEDBACK_H 6 | 7 | #include "ros_babel_fish/generation/providers/message_only_description_provider.h" 8 | #include "ros_babel_fish/babel_fish_message.h" 9 | 10 | #include 11 | #include 12 | 13 | namespace ros_babel_fish 14 | { 15 | 16 | template 17 | struct BabelFishActionFeedback_ 18 | { 19 | typedef BabelFishActionFeedback_ Type; 20 | 21 | BabelFishActionFeedback_() = default; 22 | 23 | explicit BabelFishActionFeedback_( const ContainerAllocator &allocator ) 24 | : header( allocator ), status( allocator ) { } 25 | 26 | const std::string &md5Sum() const { return md5_; } 27 | 28 | const std::string &dataType() const { return datatype_; } 29 | 30 | const std::string &definition() const { return definition_; } 31 | 32 | bool isLatched() const { return latched_; } 33 | 34 | void morph( const std::string &md5sum, const std::string &datatype, const std::string &definition, 35 | bool latched = false ) 36 | { 37 | md5_ = md5sum; 38 | datatype_ = datatype; 39 | definition_ = definition; 40 | latched_ = latched; 41 | 42 | MessageOnlyDescriptionProvider provider; 43 | MessageDescription::ConstPtr action_goal_description = provider.registerMessageByDefinition( datatype_, 44 | definition_ ); 45 | assert( action_goal_description != nullptr ); 46 | assert( action_goal_description->message_template != nullptr ); 47 | assert( action_goal_description->message_template->type == MessageTypes::Compound ); 48 | auto it = std::find( action_goal_description->message_template->compound.names.begin(), 49 | action_goal_description->message_template->compound.names.end(), "feedback" ); 50 | if ( it == action_goal_description->message_template->compound.names.end()) 51 | throw BabelFishException( "Did not find feedback in ActionFeedback message of type '" + datatype + "'!" ); 52 | int goal_index = std::distance( action_goal_description->message_template->compound.names.begin(), it ); 53 | MessageDescription::ConstPtr goal_description = provider.getMessageDescription( 54 | action_goal_description->message_template->compound.types[goal_index]->compound.datatype ); 55 | feedback.morph( goal_description ); 56 | } 57 | 58 | void morph( const MessageDescription::ConstPtr &description ) 59 | { 60 | morph( description->md5, description->datatype, description->message_definition ); 61 | } 62 | 63 | typedef ::std_msgs::Header_ _header_type; 64 | _header_type header; 65 | 66 | typedef ::actionlib_msgs::GoalStatus_ _status_type; 67 | _status_type status; 68 | 69 | typedef BabelFishMessage _feedback_type; 70 | _feedback_type feedback; 71 | 72 | typedef boost::shared_ptr > Ptr; 73 | typedef boost::shared_ptr > ConstPtr; 74 | private: 75 | std::string md5_; 76 | std::string datatype_; 77 | std::string definition_; 78 | bool latched_ = false; 79 | }; 80 | 81 | typedef BabelFishActionFeedback_ > BabelFishActionFeedback; 82 | typedef typename BabelFishActionFeedback::Ptr BabelFishActionFeedbackPtr; 83 | typedef typename BabelFishActionFeedback::ConstPtr BabelFishActionFeedbackConstPtr; 84 | } 85 | 86 | #ifndef DOXYGEN_SHOULD_SKIP_THIS 87 | 88 | // Message and service traits for serialization API 89 | namespace ros 90 | { 91 | namespace message_traits 92 | { 93 | 94 | template 95 | struct IsFixedSize<::ros_babel_fish::BabelFishActionFeedback_ > : FalseType 96 | { 97 | }; 98 | template 99 | struct IsFixedSize > : FalseType 100 | { 101 | }; 102 | 103 | template 104 | struct IsMessage<::ros_babel_fish::BabelFishActionFeedback_ > : TrueType 105 | { 106 | }; 107 | template 108 | struct IsMessage > : TrueType 109 | { 110 | }; 111 | 112 | template 113 | struct HasHeader<::ros_babel_fish::BabelFishActionFeedback_ > : TrueType 114 | { 115 | }; 116 | template 117 | struct HasHeader > : TrueType 118 | { 119 | }; 120 | 121 | template 122 | struct MD5Sum<::ros_babel_fish::BabelFishActionFeedback_ > 123 | { 124 | static const char * 125 | value( const ::ros_babel_fish::BabelFishActionFeedback_ &m ) { return m.md5Sum().c_str(); } 126 | 127 | // A BabelFishActionGoal can be of any type 128 | static const char *value() { return "*"; } 129 | }; 130 | 131 | template 132 | struct DataType<::ros_babel_fish::BabelFishActionFeedback_ > 133 | { 134 | static const char * 135 | value( const ::ros_babel_fish::BabelFishActionFeedback_ &m ) { return m.dataType().c_str(); } 136 | 137 | // A BabelFishActionGoal can be of any type 138 | static const char *value() { return "*"; } 139 | }; 140 | 141 | template 142 | struct Definition<::ros_babel_fish::BabelFishActionFeedback_ > 143 | { 144 | static const char * 145 | value( const ::ros_babel_fish::BabelFishActionFeedback_ &m ) { return m.definition().c_str(); } 146 | 147 | // A BabelFishActionGoal can be of any type 148 | static const char *value() { return "*"; } 149 | }; 150 | } // message_traits 151 | 152 | namespace serialization 153 | { 154 | 155 | template 156 | struct Serializer<::ros_babel_fish::BabelFishActionFeedback_ > 157 | { 158 | template 159 | inline static void write( Stream &stream, const ::ros_babel_fish::BabelFishActionFeedback_ &m ) 160 | { 161 | stream.next( m.header ); 162 | stream.next( m.status ); 163 | m.feedback.write( stream ); 164 | } 165 | 166 | template 167 | inline static void read( Stream &stream, ::ros_babel_fish::BabelFishActionFeedback_ &m ) 168 | { 169 | stream.next( m.header ); 170 | stream.next( m.status ); 171 | m.feedback.read( stream ); 172 | } 173 | 174 | inline static uint32_t serializedLength( const ::ros_babel_fish::BabelFishActionFeedback_ &m ) 175 | { 176 | LStream stream; 177 | stream.next( m.header ); 178 | stream.next( m.status ); 179 | return stream.getLength() + m.feedback.size(); 180 | } 181 | }; 182 | 183 | template 184 | struct PreDeserialize<::ros_babel_fish::BabelFishActionFeedback_ > 185 | { 186 | static void 187 | notify( const PreDeserializeParams<::ros_babel_fish::BabelFishActionFeedback_ > ¶ms ) 188 | { 189 | std::string md5 = (*params.connection_header)["md5sum"]; 190 | std::string datatype = (*params.connection_header)["type"]; 191 | std::string msg_def = (*params.connection_header)["message_definition"]; 192 | std::string latching = (*params.connection_header)["latching"]; 193 | 194 | params.message->morph( md5, datatype, msg_def, latching == "1" ); 195 | } 196 | }; 197 | } // serialization 198 | 199 | } // ros 200 | 201 | #endif // DOXYGEN_SHOULD_SKIP_THIS 202 | 203 | #endif //ROS_BABEL_FISH_BABEL_FISH_ACTION_FEEDBACK_H 204 | -------------------------------------------------------------------------------- /ros_babel_fish/src/generation/providers/integrated_description_provider.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "ros_babel_fish/generation/providers/integrated_description_provider.h" 5 | 6 | #include 7 | 8 | #include 9 | #include 10 | #include 11 | 12 | namespace fs = std::experimental::filesystem; 13 | 14 | namespace ros_babel_fish 15 | { 16 | 17 | namespace 18 | { 19 | #ifdef _WIN32 20 | const std::string OS_PATHSEP(";"); 21 | #else 22 | const std::string OS_PATHSEP( ":" ); 23 | #endif 24 | 25 | const std::string CATKIN_MARKER_FILE = ".catkin"; 26 | 27 | std::vector findWorkspaceShares() 28 | { 29 | char *cmake_prefix_path = std::getenv( "CMAKE_PREFIX_PATH" ); 30 | if ( cmake_prefix_path == nullptr ) return {}; 31 | size_t length = std::strlen( cmake_prefix_path ); 32 | std::vector paths; 33 | std::string path; 34 | size_t path_sep_index = 0; 35 | for ( size_t i = 0; i <= length; ++i ) 36 | { 37 | if ( i == length || (cmake_prefix_path[i] == OS_PATHSEP[path_sep_index] && ++path_sep_index == OS_PATHSEP.length())) 38 | { 39 | if ( !path.empty()) 40 | { 41 | fs::path catkin_marker_path = fs::path( path ) / CATKIN_MARKER_FILE; 42 | fs::path share_path = fs::path( path ) / "share"; 43 | if ( fs::is_regular_file( catkin_marker_path ) && fs::is_directory( share_path )) 44 | { 45 | paths.push_back( share_path ); 46 | } 47 | } 48 | path_sep_index = 0; 49 | path.clear(); 50 | continue; 51 | } 52 | path_sep_index = 0; 53 | path.push_back( cmake_prefix_path[i] ); 54 | } 55 | return paths; 56 | } 57 | } 58 | 59 | IntegratedDescriptionProvider::IntegratedDescriptionProvider() 60 | { 61 | ros::V_string packages; 62 | if ( !ros::package::getAll( packages )) 63 | throw BabelFishException( "Failed to retrieve package paths, will not be able to look up message definitions!" ); 64 | 65 | 66 | std::vector workspace_shares = findWorkspaceShares(); 67 | for ( auto &pkg : packages ) 68 | { 69 | fs::path base_path = ros::package::getPath( pkg ); 70 | std::vector msg_paths, srv_paths; 71 | 72 | // First check directories returned by ros::package::getPath 73 | fs::path msg_path = base_path / "msg"; 74 | if ( fs::is_directory( msg_path )) 75 | msg_paths.push_back( msg_path.string()); 76 | fs::path srv_path = base_path / "srv"; 77 | if ( fs::is_directory( srv_path )) 78 | srv_paths.push_back( srv_path.string()); 79 | 80 | // Then check first result in workspaces 81 | for ( const fs::path &workspace_share : workspace_shares ) 82 | { 83 | fs::path project_path = workspace_share / pkg; 84 | if ( fs::is_directory( project_path )) 85 | { 86 | if ( project_path == base_path ) break; 87 | fs::path workspace_msg_path = project_path / "msg"; 88 | if ( fs::is_directory( workspace_msg_path )) 89 | msg_paths.push_back( workspace_msg_path.string()); 90 | fs::path workspace_srv_path = project_path / "srv"; 91 | if ( fs::is_directory( workspace_srv_path )) 92 | srv_paths.push_back( workspace_srv_path.string()); 93 | // Only add the first match and only if it differed from the base_path 94 | break; 95 | } 96 | } 97 | if ( !msg_paths.empty()) msg_paths_.insert( { pkg, msg_paths } ); 98 | if ( !srv_paths.empty()) srv_paths_.insert( { pkg, srv_paths } ); 99 | } 100 | } 101 | 102 | MessageDescription::ConstPtr IntegratedDescriptionProvider::getMessageDescriptionImpl( const std::string &type ) 103 | { 104 | if ( type == "Header" ) return getMessageDescription( "std_msgs/Header" ); 105 | std::string::size_type pos_separator = type.find( '/' ); 106 | if ( pos_separator == std::string::npos ) 107 | { 108 | ROS_WARN_NAMED( "RosBabelFish", "Type '%s' is not a valid message type!", type.c_str()); 109 | return nullptr; 110 | } 111 | std::string package = type.substr( 0, pos_separator ); 112 | std::string msg_type = type.substr( package.length() + 1 ); 113 | auto it = msg_paths_.find( package ); 114 | if ( it == msg_paths_.end()) 115 | { 116 | ROS_WARN_NAMED( "RosBabelFish", "Could not find package '%s' in msg paths!", package.c_str()); 117 | return nullptr; 118 | } 119 | const std::vector &package_paths = it->second; 120 | fs::path message_path; 121 | for ( const auto &package_path : package_paths ) 122 | { 123 | fs::path p = fs::path( package_path ) / (msg_type + ".msg"); 124 | if ( !fs::is_regular_file( p )) continue; 125 | message_path = p; 126 | break; 127 | } 128 | if ( message_path.empty()) 129 | { 130 | ROS_WARN_NAMED( "RosBabelFish", "Could not find message of type '%s' in package '%s'!", msg_type.c_str(), 131 | package.c_str()); 132 | return nullptr; 133 | } 134 | 135 | // Load message specification from file 136 | std::ifstream file_input( message_path ); 137 | file_input.seekg( 0, std::ios::end ); 138 | std::string specification; 139 | specification.resize( file_input.tellg()); 140 | file_input.seekg( 0, std::ios::beg ); 141 | file_input.read( &specification[0], specification.size()); 142 | file_input.close(); 143 | 144 | return registerMessage( type, specification ); 145 | } 146 | 147 | ServiceDescription::ConstPtr IntegratedDescriptionProvider::getServiceDescriptionImpl( const std::string &type ) 148 | { 149 | std::string::size_type pos_separator = type.find( '/' ); 150 | if ( pos_separator == std::string::npos ) 151 | { 152 | ROS_WARN_NAMED( "RosBabelFish", "Type '%s' is not a valid service type!", type.c_str()); 153 | return nullptr; 154 | } 155 | std::string package = type.substr( 0, pos_separator ); 156 | std::string msg_type = type.substr( package.length() + 1 ); 157 | auto it = srv_paths_.find( package ); 158 | if ( it == srv_paths_.end()) 159 | { 160 | ROS_WARN_NAMED( "RosBabelFish", "Could not find package '%s' in srv paths!", package.c_str()); 161 | return nullptr; 162 | } 163 | const std::vector &package_paths = it->second; 164 | fs::path service_path; 165 | for ( const auto &package_path : package_paths ) 166 | { 167 | fs::path p = fs::path( package_path ) / (msg_type + ".srv"); 168 | if ( !fs::is_regular_file( p )) continue; 169 | service_path = p; 170 | break; 171 | } 172 | if ( service_path.empty()) 173 | { 174 | ROS_WARN_NAMED( "RosBabelFish", "Could not find service of type '%s' in package '%s'!", msg_type.c_str(), 175 | package.c_str()); 176 | return nullptr; 177 | } 178 | 179 | // Load service specification from file 180 | std::ifstream file_input( service_path ); 181 | file_input.seekg( 0, std::ios::end ); 182 | std::string spec; 183 | spec.resize( file_input.tellg()); 184 | file_input.seekg( 0, std::ios::beg ); 185 | file_input.read( &spec[0], spec.size()); 186 | file_input.close(); 187 | if ( spec.length() < 3 ) 188 | { 189 | ROS_ERROR_NAMED( "RosBabelFish", "Service specification for type '%s' in package '%s' was invalid!", 190 | msg_type.c_str(), package.c_str()); 191 | return nullptr; 192 | } 193 | 194 | // Extract service request and response specifications which are divided by '---' on a blank line 195 | std::string::size_type end = 0; 196 | if ( spec[0] != '-' || spec[1] != '-' || spec[2] != '-' ) 197 | end = spec.find( "\n---" ); 198 | std::string request( spec, 0, end ); 199 | 200 | std::string response; 201 | if ( end != std::string::npos ) 202 | { 203 | end = spec.find( '\n', end + 1 ); 204 | if ( end != std::string::npos && end + 1 < spec.length()) 205 | response = std::string( spec, end + 1 ) + "\n"; 206 | } 207 | 208 | return registerService( type, spec, request, response ); 209 | } 210 | } // ros_babel_fish 211 | -------------------------------------------------------------------------------- /ros_babel_fish/examples/any_subscriber.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | 11 | /*! 12 | * The following example demonstrates how to subscribe to a topic of any type, retrieve type information such as the 13 | * topic's datatype, the MD5 sum and the message definition, and traverse the message's content. 14 | * The datatype, MD5 sum, message definition and the message's content are dumped to the console whenever a new message 15 | * is received. 16 | */ 17 | 18 | void dumpMessageContent( const ros_babel_fish::BabelFishMessage::ConstPtr &msg ); 19 | 20 | void callback( const ros_babel_fish::BabelFishMessage::ConstPtr &msg ) 21 | { 22 | std::cout << "Message received!" << std::endl; 23 | std::cout << "Data Type:" << std::endl; 24 | std::cout << msg->dataType() << std::endl; 25 | std::cout << "MD5:" << std::endl; 26 | std::cout << msg->md5Sum() << std::endl; 27 | std::cout << "Message Definition:" << std::endl; 28 | std::cout << msg->definition() << std::endl; 29 | std::cout << "Message Content:" << std::endl; 30 | dumpMessageContent( msg ); 31 | std::cout << std::endl; 32 | } 33 | 34 | 35 | ros_babel_fish::BabelFish *fish; 36 | 37 | int main( int argc, char **argv ) 38 | { 39 | if ( argc != 2 ) 40 | { 41 | std::cout << "Invalid argument!" << std::endl; 42 | std::cout << "Usage: any_subscriber [TOPIC]" << std::endl; 43 | return 1; 44 | } 45 | ros::init( argc, argv, "ros_babel_fish_any_subscriber" ); 46 | ros::NodeHandle nh; 47 | std::string topic = argv[1]; 48 | 49 | fish = new ros_babel_fish::BabelFish; 50 | ros::Subscriber sub = nh.subscribe( topic, 1, &callback ); 51 | ros::spin(); 52 | delete fish; 53 | } 54 | 55 | using namespace ros_babel_fish; 56 | 57 | template 58 | void printArray( const ArrayMessage &message ) 59 | { 60 | std::cout << "["; 61 | for ( size_t i = 0; i < message.length(); ++i ) 62 | { 63 | std::cout << message[i]; 64 | if ( i != message.length() - 1 ) std::cout << ", "; 65 | } 66 | std::cout << "]" << std::endl; 67 | } 68 | 69 | template<> 70 | void printArray( const ArrayMessage &message ) 71 | { 72 | std::cout << "["; 73 | for ( size_t i = 0; i < message.length(); ++i ) 74 | { 75 | std::cout << static_cast(message[i]); 76 | if ( i != message.length() - 1 ) std::cout << ", "; 77 | } 78 | std::cout << "]" << std::endl; 79 | } 80 | 81 | void dumpMessageContent( const Message &message, const std::string &prefix = "" ) 82 | { 83 | if ( message.type() == MessageTypes::Compound ) 84 | { 85 | auto &compound = message.as(); 86 | std::cout << std::endl; 87 | for ( size_t i = 0; i < compound.keys().size(); ++i ) 88 | { 89 | std::cout << prefix << compound.keys()[i] << ": "; 90 | dumpMessageContent( *compound.values()[i], prefix + " " ); 91 | if ( i != compound.keys().size() - 1 ) std::cout << std::endl; 92 | } 93 | } 94 | else if ( message.type() == MessageTypes::Array ) 95 | { 96 | auto &base = message.as(); 97 | switch ( base.elementType()) 98 | { 99 | case MessageTypes::None: 100 | break; 101 | case MessageTypes::Bool: 102 | printArray( base.as>()); 103 | break; 104 | case MessageTypes::UInt8: 105 | printArray( base.as>()); 106 | break; 107 | case MessageTypes::UInt16: 108 | printArray( base.as>()); 109 | break; 110 | case MessageTypes::UInt32: 111 | printArray( base.as>()); 112 | break; 113 | case MessageTypes::UInt64: 114 | printArray( base.as>()); 115 | break; 116 | case MessageTypes::Int8: 117 | printArray( base.as>()); 118 | break; 119 | case MessageTypes::Int16: 120 | printArray( base.as>()); 121 | break; 122 | case MessageTypes::Int32: 123 | printArray( base.as>()); 124 | break; 125 | case MessageTypes::Int64: 126 | printArray( base.as>()); 127 | break; 128 | case MessageTypes::Float32: 129 | printArray( base.as>()); 130 | break; 131 | case MessageTypes::Float64: 132 | printArray( base.as>()); 133 | break; 134 | case MessageTypes::Time: 135 | printArray( base.as>()); 136 | break; 137 | case MessageTypes::Duration: 138 | printArray( base.as>()); 139 | break; 140 | case MessageTypes::String: 141 | printArray( base.as>()); 142 | break; 143 | case MessageTypes::Compound: 144 | case MessageTypes::Array: // Arrays of arrays are actually not supported in the ROS msg format 145 | { 146 | std::cout << std::endl; 147 | auto &array = base.as>(); 148 | for ( size_t i = 0; i < array.length(); ++i ) 149 | { 150 | std::cout << prefix << "- "; 151 | dumpMessageContent( array[i], prefix + " " ); 152 | } 153 | break; 154 | } 155 | } 156 | } 157 | else 158 | { 159 | switch ( message.type()) 160 | { 161 | case MessageTypes::Array: 162 | case MessageTypes::Compound: 163 | case MessageTypes::None: 164 | break; 165 | case MessageTypes::Bool: 166 | std::cout << (message.as>().getValue() ? "true" : "false"); 167 | break; 168 | case MessageTypes::UInt8: 169 | std::cout << static_cast(message.as>().getValue()); 170 | break; 171 | case MessageTypes::UInt16: 172 | std::cout << message.value(); // The statement above can be simplified using this convenience method 173 | break; 174 | case MessageTypes::UInt32: 175 | std::cout << message.value(); 176 | break; 177 | case MessageTypes::UInt64: 178 | std::cout << message.value(); 179 | break; 180 | case MessageTypes::Int8: 181 | std::cout << message.value(); 182 | break; 183 | case MessageTypes::Int16: 184 | std::cout << message.value(); 185 | break; 186 | case MessageTypes::Int32: 187 | std::cout << message.value(); 188 | break; 189 | case MessageTypes::Int64: 190 | std::cout << message.value(); 191 | break; 192 | case MessageTypes::Float32: 193 | std::cout << message.value(); 194 | break; 195 | case MessageTypes::Float64: 196 | std::cout << message.value(); 197 | break; 198 | case MessageTypes::Time: 199 | std::cout << message.value(); 200 | break; 201 | case MessageTypes::Duration: 202 | std::cout << message.value(); 203 | break; 204 | case MessageTypes::String: 205 | std::cout << message.value(); 206 | break; 207 | } 208 | } 209 | } 210 | 211 | void dumpMessageContent( const BabelFishMessage::ConstPtr &msg ) 212 | { 213 | TranslatedMessage::Ptr translated = fish->translateMessage( msg ); 214 | dumpMessageContent( *translated->translated_message ); 215 | } 216 | -------------------------------------------------------------------------------- /ros_babel_fish/test/service_lookup.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Stefan Fabian on 15.09.19. 3 | // 4 | 5 | #include 6 | #include 7 | 8 | #include 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | #include 16 | 17 | // Workaround because GetParamRequest has a member called default which is a reserved keyword in C++ 18 | #define default mdefault 19 | 20 | #include 21 | 22 | #undef default 23 | 24 | #include 25 | #include 26 | #include 27 | #include 28 | #include 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include 40 | #include 41 | #include 42 | #include 43 | #include 44 | #include 45 | 46 | #include 47 | #include 48 | 49 | using namespace ros_babel_fish; 50 | 51 | template 52 | ::testing::AssertionResult compareDescription() 53 | { 54 | namespace st = ros::service_traits; 55 | namespace mt = ros::message_traits; 56 | { 57 | SCOPED_TRACE( "Service description lookup" ); 58 | ProviderType provider; 59 | ServiceDescription::ConstPtr desc = provider.getServiceDescription( st::DataType::value()); 60 | if ( desc == nullptr ) 61 | return ::testing::AssertionFailure() << "Failed to get message description for: " 62 | << st::DataType::value(); 63 | if ( st::MD5Sum::value() != desc->md5 ) 64 | return ::testing::AssertionFailure() << "MD5 Sum differed!" << std::endl 65 | << "BF MD5: " << desc->md5 << std::endl 66 | << "MSG MD5: " << st::MD5Sum::value(); 67 | if ( st::DataType::value() != desc->datatype ) 68 | return ::testing::AssertionFailure() << "Datatype differed!" << std::endl 69 | << "BF Datatype: " << desc->datatype << std::endl 70 | << "MSG Datatype: " << st::DataType::value(); 71 | 72 | { 73 | if ( mt::datatype() != desc->request->datatype ) 74 | return ::testing::AssertionFailure() << "Request Datatype differed!" << std::endl 75 | << "BF Datatype: " << desc->request->datatype << std::endl 76 | << "MSG Datatype: " << mt::datatype(); 77 | if ( mt::md5sum() != desc->request->md5 ) 78 | return ::testing::AssertionFailure() << "Request MD5 Sum differed!" << std::endl 79 | << "BF MD5: " << desc->request->md5 << std::endl 80 | << "MSG MD5: " << mt::md5sum(); 81 | if ( mt::definition() != desc->request->message_definition ) 82 | return ::testing::AssertionFailure() << "Request Definition differed!" << std::endl 83 | << "--------------------------- BF Definition: ---------------------------" 84 | << std::endl << desc->request->message_definition << std::endl 85 | << "--------------------------- MSG Definition: ---------------------------" 86 | << std::endl << mt::Definition::value(); 87 | } 88 | 89 | { 90 | SCOPED_TRACE( "Response" ); 91 | if ( mt::datatype() != desc->response->datatype ) 92 | return ::testing::AssertionFailure() << "Response Datatype differed!" << std::endl 93 | << "BF Datatype: " << desc->response->datatype << std::endl 94 | << "MSG Datatype: " << mt::datatype(); 95 | if ( mt::md5sum() != desc->response->md5 ) 96 | return ::testing::AssertionFailure() << "Response MD5 Sum differed!" << std::endl 97 | << "BF MD5: " << desc->response->md5 << std::endl 98 | << "MSG MD5: " << mt::md5sum(); 99 | if ( mt::definition() != desc->response->message_definition ) 100 | return ::testing::AssertionFailure() << "Response Definition differed!" << std::endl 101 | << "--------------------------- BF Definition: ---------------------------" 102 | << std::endl << desc->response->message_definition << std::endl 103 | << "--------------------------- MSG Definition: ---------------------------" 104 | << std::endl << mt::Definition::value(); 105 | } 106 | } 107 | return ::testing::AssertionSuccess(); 108 | } 109 | 110 | TEST( ServiceLookupTest, integratedDescriptionProvider ) 111 | { 112 | EXPECT_TRUE((compareDescription())); 113 | 114 | EXPECT_TRUE((compareDescription())); 115 | EXPECT_TRUE((compareDescription())); 116 | EXPECT_TRUE((compareDescription())); 117 | 118 | EXPECT_TRUE((compareDescription())); 119 | EXPECT_TRUE((compareDescription())); 120 | EXPECT_TRUE((compareDescription())); 121 | EXPECT_TRUE((compareDescription())); 122 | EXPECT_TRUE((compareDescription())); 123 | EXPECT_TRUE((compareDescription())); 124 | EXPECT_TRUE((compareDescription())); 125 | EXPECT_TRUE((compareDescription())); 126 | EXPECT_TRUE((compareDescription())); 127 | EXPECT_TRUE((compareDescription())); 128 | EXPECT_TRUE((compareDescription())); 129 | EXPECT_TRUE((compareDescription())); 130 | EXPECT_TRUE((compareDescription())); 131 | EXPECT_TRUE((compareDescription())); 132 | EXPECT_TRUE((compareDescription())); 133 | EXPECT_TRUE((compareDescription())); 134 | EXPECT_TRUE((compareDescription())); 135 | EXPECT_TRUE((compareDescription())); 136 | EXPECT_TRUE((compareDescription())); 137 | EXPECT_TRUE((compareDescription())); 138 | EXPECT_TRUE((compareDescription())); 139 | EXPECT_TRUE((compareDescription())); 140 | EXPECT_TRUE((compareDescription())); 141 | EXPECT_TRUE((compareDescription())); 142 | } 143 | 144 | TEST( ServiceLookupTest, messageOnlyDescriptionProvider ) 145 | { 146 | namespace st = ros::service_traits; 147 | MessageOnlyDescriptionProvider provider; 148 | EXPECT_THROW( provider.getServiceDescription( st::datatype()), BabelFishException ); 149 | } 150 | 151 | int main( int argc, char **argv ) 152 | { 153 | testing::InitGoogleTest( &argc, argv ); 154 | ros::init( argc, argv, "test_message_lookup" ); 155 | ros::NodeHandle nh; 156 | return RUN_ALL_TESTS(); 157 | } 158 | -------------------------------------------------------------------------------- /ros_babel_fish/include/ros_babel_fish/actionlib/babel_fish_action_goal.h: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2020 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #ifndef ROS_BABEL_FISH_BABEL_FISH_ACTION_GOAL_H 5 | #define ROS_BABEL_FISH_BABEL_FISH_ACTION_GOAL_H 6 | 7 | #include "ros_babel_fish/generation/providers/message_only_description_provider.h" 8 | #include "ros_babel_fish/babel_fish_message.h" 9 | 10 | #include 11 | #include 12 | 13 | namespace ros_babel_fish 14 | { 15 | 16 | template 17 | struct BabelFishActionGoal_ 18 | { 19 | typedef BabelFishActionGoal_ Type; 20 | 21 | BabelFishActionGoal_() = default; 22 | 23 | explicit BabelFishActionGoal_( const ContainerAllocator &allocator ) : header( allocator ), goal_id( allocator ) { } 24 | 25 | const std::string &md5Sum() const 26 | { 27 | if ( md5_.empty()) initMessageForGoal(); 28 | return md5_; 29 | } 30 | 31 | const std::string &dataType() const 32 | { 33 | if ( datatype_.empty()) initMessageForGoal(); 34 | return datatype_; 35 | } 36 | 37 | const std::string &definition() const 38 | { 39 | if ( definition_.empty()) initMessageForGoal(); 40 | return definition_; 41 | } 42 | 43 | bool isLatched() const { return latched_; } 44 | 45 | void morph( const std::string &md5sum, const std::string &datatype, const std::string &definition, 46 | bool latched = false ) 47 | { 48 | md5_ = md5sum; 49 | datatype_ = datatype; 50 | definition_ = definition; 51 | latched_ = latched; 52 | 53 | MessageOnlyDescriptionProvider provider; 54 | MessageDescription::ConstPtr action_goal_description = provider.registerMessageByDefinition( datatype_, 55 | definition_ ); 56 | assert( action_goal_description != nullptr ); 57 | assert( action_goal_description->message_template != nullptr ); 58 | assert( action_goal_description->message_template->type == MessageTypes::Compound ); 59 | auto it = std::find( action_goal_description->message_template->compound.names.begin(), 60 | action_goal_description->message_template->compound.names.end(), "goal" ); 61 | if ( it == action_goal_description->message_template->compound.names.end()) 62 | throw BabelFishException( "Did not find goal in ActionGoal message of type '" + datatype + "'!" ); 63 | int goal_index = std::distance( action_goal_description->message_template->compound.names.begin(), it ); 64 | MessageDescription::ConstPtr goal_description = provider.getMessageDescription( 65 | action_goal_description->message_template->compound.types[goal_index]->compound.datatype ); 66 | goal.morph( goal_description ); 67 | } 68 | 69 | void morph( const MessageDescription::ConstPtr &description ) 70 | { 71 | morph( description->md5, description->datatype, description->message_definition ); 72 | } 73 | 74 | typedef ::std_msgs::Header_ _header_type; 75 | _header_type header; 76 | typedef ::actionlib_msgs::GoalID_ _goal_id_type; 77 | _goal_id_type goal_id; 78 | 79 | typedef BabelFishMessage _goal_type; 80 | _goal_type goal; 81 | 82 | typedef boost::shared_ptr > Ptr; 83 | typedef boost::shared_ptr > ConstPtr; 84 | private: 85 | 86 | void initMessageForGoal() const 87 | { 88 | if ( goal.dataType().empty()) return; 89 | 90 | // This method initializes the md5 sum, datatype and definition based on the values provided in the goal BabelFishMessage 91 | MessageOnlyDescriptionProvider provider; 92 | provider.registerMessageByDefinition( ros::message_traits::datatype(), 93 | ros::message_traits::definition()); 94 | provider.registerMessageByDefinition( ros::message_traits::datatype<_goal_id_type>(), 95 | ros::message_traits::definition<_goal_id_type>()); 96 | provider.registerMessageByDefinition( goal.dataType(), goal.definition()); 97 | std::string datatype = goal.dataType(); 98 | assert( datatype.substr( datatype.length() - 4 ) == "Goal" ); 99 | datatype = datatype.substr( 0, datatype.length() - 4 ) + "ActionGoal"; 100 | MessageDescription::ConstPtr description = 101 | provider.registerMessageBySpecification( datatype, std::string( "Header header\n" ) 102 | + ros::message_traits::datatype<_goal_id_type>() + " goal_id\n" 103 | + goal.dataType() + " goal\n" ); 104 | md5_ = description->md5; 105 | datatype_ = datatype; 106 | definition_ = description->message_definition; 107 | } 108 | 109 | mutable std::string md5_; 110 | mutable std::string datatype_; 111 | mutable std::string definition_; 112 | bool latched_ = false; 113 | }; 114 | 115 | typedef BabelFishActionGoal_ > BabelFishActionGoal; 116 | typedef typename BabelFishActionGoal::Ptr BabelFishActionGoalPtr; 117 | typedef typename BabelFishActionGoal::ConstPtr BabelFishActionGoalConstPtr; 118 | } 119 | 120 | #ifndef DOXYGEN_SHOULD_SKIP_THIS 121 | 122 | // Message and service traits for serialization API 123 | namespace ros 124 | { 125 | namespace message_traits 126 | { 127 | 128 | template 129 | struct IsFixedSize<::ros_babel_fish::BabelFishActionGoal_ > : FalseType 130 | { 131 | }; 132 | template 133 | struct IsFixedSize > : FalseType 134 | { 135 | }; 136 | 137 | template 138 | struct IsMessage<::ros_babel_fish::BabelFishActionGoal_ > : TrueType 139 | { 140 | }; 141 | template 142 | struct IsMessage > : TrueType 143 | { 144 | }; 145 | 146 | template 147 | struct HasHeader<::ros_babel_fish::BabelFishActionGoal_ > : TrueType 148 | { 149 | }; 150 | template 151 | struct HasHeader > : TrueType 152 | { 153 | }; 154 | 155 | template 156 | struct MD5Sum<::ros_babel_fish::BabelFishActionGoal_ > 157 | { 158 | static const char * 159 | value( const ::ros_babel_fish::BabelFishActionGoal_ &m ) { return m.md5Sum().c_str(); } 160 | 161 | // A BabelFishActionGoal can be of any type 162 | static const char *value() { return "*"; } 163 | }; 164 | 165 | template 166 | struct DataType<::ros_babel_fish::BabelFishActionGoal_ > 167 | { 168 | static const char * 169 | value( const ::ros_babel_fish::BabelFishActionGoal_ &m ) { return m.dataType().c_str(); } 170 | 171 | // A BabelFishActionGoal can be of any type 172 | static const char *value() { return "*"; } 173 | }; 174 | 175 | template 176 | struct Definition<::ros_babel_fish::BabelFishActionGoal_ > 177 | { 178 | static const char * 179 | value( const ::ros_babel_fish::BabelFishActionGoal_ &m ) { return m.definition().c_str(); } 180 | 181 | // A BabelFishActionGoal can be of any type 182 | static const char *value() { return "*"; } 183 | }; 184 | } // message_traits 185 | 186 | namespace serialization 187 | { 188 | 189 | template 190 | struct Serializer<::ros_babel_fish::BabelFishActionGoal_ > 191 | { 192 | template 193 | inline static void write( Stream &stream, const ::ros_babel_fish::BabelFishActionGoal_ &m ) 194 | { 195 | stream.next( m.header ); 196 | stream.next( m.goal_id ); 197 | m.goal.write( stream ); 198 | } 199 | 200 | template 201 | inline static void read( Stream &stream, ::ros_babel_fish::BabelFishActionGoal_ &m ) 202 | { 203 | stream.next( m.header ); 204 | stream.next( m.goal_id ); 205 | m.goal.read( stream ); 206 | } 207 | 208 | inline static uint32_t serializedLength( const ::ros_babel_fish::BabelFishActionGoal_ &m ) 209 | { 210 | LStream stream; 211 | stream.next( m.header ); 212 | stream.next( m.goal_id ); 213 | return stream.getLength() + m.goal.size(); 214 | } 215 | }; 216 | 217 | template 218 | struct PreDeserialize<::ros_babel_fish::BabelFishActionGoal_ > 219 | { 220 | static void notify( const PreDeserializeParams<::ros_babel_fish::BabelFishActionGoal_ > ¶ms ) 221 | { 222 | std::string md5 = (*params.connection_header)["md5sum"]; 223 | std::string datatype = (*params.connection_header)["type"]; 224 | std::string msg_def = (*params.connection_header)["message_definition"]; 225 | std::string latching = (*params.connection_header)["latching"]; 226 | 227 | params.message->morph( md5, datatype, msg_def, latching == "1" ); 228 | } 229 | }; 230 | } // serialization 231 | 232 | } // ros 233 | 234 | #endif // DOXYGEN_SHOULD_SKIP_THIS 235 | 236 | #endif // ROS_BABEL_FISH_BABEL_FISH_ACTION_GOAL_H 237 | -------------------------------------------------------------------------------- /ros_babel_fish/src/babel_fish.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "ros_babel_fish/babel_fish.h" 5 | 6 | #include "ros_babel_fish/generation/providers/integrated_description_provider.h" 7 | #include "ros_babel_fish/generation/message_creation.h" 8 | #include "ros_babel_fish/message_types.h" 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | 16 | namespace ros_babel_fish 17 | { 18 | 19 | BabelFish::BabelFish() : BabelFish( std::make_shared()) { } 20 | 21 | BabelFish::BabelFish( DescriptionProvider::Ptr description_provider ) 22 | : description_provider_( std::move( description_provider )) 23 | { 24 | if ( description_provider_ == nullptr ) 25 | throw BabelFishException( "DescriptionProvider passed to BabelFish was nullptr!" ); 26 | } 27 | 28 | BabelFish::~BabelFish() = default; 29 | 30 | TranslatedMessage::Ptr BabelFish::translateMessage( const IBabelFishMessage::ConstPtr &msg ) 31 | { 32 | const MessageDescription::ConstPtr &message_description = description_provider_->getMessageDescription( *msg ); 33 | if ( message_description == nullptr ) 34 | { 35 | throw BabelFishException( 36 | "BabelFish failed to get message description for received message of type: " + msg->dataType()); 37 | } 38 | const MessageTemplate::ConstPtr &msg_template = message_description->message_template; 39 | const uint8_t *stream = msg->buffer(); 40 | size_t bytes_read = 0; 41 | if ( stream == nullptr ) 42 | { 43 | Message::Ptr translated = std::make_shared( msg_template ); 44 | return std::make_shared( msg, translated ); 45 | } 46 | 47 | Message::Ptr translated( CompoundMessage::fromStream( msg_template, stream, msg->size(), bytes_read )); 48 | if ( bytes_read != msg->size()) 49 | throw BabelFishException( "Translated message of type '" + msg->dataType() + "' did not consume all message bytes!" ); 50 | return std::make_shared( msg, translated ); 51 | } 52 | 53 | Message::Ptr BabelFish::translateMessage( const IBabelFishMessage &msg ) 54 | { 55 | const MessageDescription::ConstPtr &message_description = description_provider_->getMessageDescription( msg ); 56 | if ( message_description == nullptr ) 57 | { 58 | throw BabelFishException( 59 | "BabelFish failed to get message description for received message of type: " + msg.dataType()); 60 | } 61 | const MessageTemplate::ConstPtr &msg_template = message_description->message_template; 62 | const uint8_t *stream = msg.buffer(); 63 | size_t bytes_read = 0; 64 | if ( stream == nullptr ) 65 | { 66 | return std::make_shared( msg_template ); 67 | } 68 | 69 | Message::Ptr translated( CompoundMessage::fromStream( msg_template, stream, msg.size(), bytes_read )); 70 | if ( bytes_read != msg.size()) 71 | throw BabelFishException( "Translated message of type '" + msg.dataType() + "' did not consume all message bytes!" ); 72 | return translated; 73 | } 74 | 75 | BabelFishMessage::Ptr BabelFish::translateMessage( const Message::ConstPtr &msg ) 76 | { 77 | return translateMessage( *msg ); 78 | } 79 | 80 | BabelFishMessage::Ptr BabelFish::translateMessage( const Message &msg ) 81 | { 82 | return translateMessage( msg, false ); 83 | } 84 | 85 | BabelFishMessage::Ptr BabelFish::translateMessage( const Message &msg, bool latched ) 86 | { 87 | auto compound_msg = dynamic_cast(&msg); 88 | if ( compound_msg == nullptr ) 89 | throw BabelFishException( "Tried to translate message that is not a compound message!" ); 90 | 91 | BabelFishMessage::Ptr result( new BabelFishMessage()); 92 | const MessageDescription::ConstPtr &description = description_provider_->getMessageDescription( 93 | compound_msg->datatype()); 94 | if ( description == nullptr ) 95 | { 96 | throw BabelFishException( "BabelFish doesn't know a message of type: " + compound_msg->datatype()); 97 | } 98 | result->morph( description->md5, description->datatype, description->message_definition, latched ); 99 | result->allocate( msg._sizeInBytes()); 100 | msg.writeToStream( result->buffer()); 101 | return result; 102 | } 103 | 104 | bool BabelFish::translateMessage( const Message &msg, BabelFishMessage &result ) 105 | { 106 | auto compound_msg = dynamic_cast(&msg); 107 | if ( compound_msg == nullptr ) 108 | throw BabelFishException( "Tried to translate message that is not a compound message!" ); 109 | const MessageDescription::ConstPtr &description = description_provider_->getMessageDescription( 110 | compound_msg->datatype()); 111 | if ( description == nullptr ) 112 | { 113 | throw BabelFishException( "BabelFish doesn't know a message of type: " + compound_msg->datatype()); 114 | } 115 | result.morph( description->md5, description->datatype, description->message_definition, false ); 116 | result.allocate( msg._sizeInBytes()); 117 | msg.writeToStream( result.buffer()); 118 | return true; 119 | } 120 | 121 | ros::Publisher BabelFish::advertise( ros::NodeHandle &nh, const std::string &type, const std::string &topic, 122 | uint32_t queue_size, bool latch, 123 | const ros::SubscriberStatusCallback &connect_cb, 124 | const ros::SubscriberStatusCallback &disconnect_cb ) 125 | { 126 | const MessageDescription::ConstPtr &description = description_provider_->getMessageDescription( type ); 127 | if ( description == nullptr ) 128 | { 129 | throw BabelFishException( "BabelFish doesn't know a message of type: " + type ); 130 | } 131 | ros::AdvertiseOptions opts( topic, queue_size, description->md5, description->datatype, 132 | description->message_definition, connect_cb, disconnect_cb ); 133 | opts.latch = latch; 134 | 135 | return nh.advertise( opts ); 136 | } 137 | 138 | ros::ServiceServer BabelFish::advertiseService( ros::NodeHandle &nh, const std::string &type, 139 | const std::string &service, 140 | const std::function &callback ) 141 | { 142 | const ServiceDescription::ConstPtr &description = description_provider_->getServiceDescription( type ); 143 | if ( description == nullptr ) 144 | { 145 | throw BabelFishException( "BabelFish doesn't know a service of type: " + type ); 146 | } 147 | ros::AdvertiseServiceOptions opts; 148 | opts.datatype = description->datatype; 149 | opts.service = service; 150 | opts.req_datatype = description->request->datatype; 151 | opts.res_datatype = description->response->datatype; 152 | opts.md5sum = description->md5; 153 | opts.helper = ros::ServiceCallbackHelperPtr( 154 | new ros::ServiceCallbackHelperT>( 155 | [ this, &callback ]( BabelFishMessage &req, BabelFishMessage &res ) -> bool 156 | { 157 | Message::Ptr translated_req = translateMessage( req ); 158 | Message::Ptr translated_res = translateMessage( res ); 159 | bool result = callback( *translated_req, *translated_res ); 160 | if ( !translateMessage( *translated_res, res )) 161 | { 162 | ROS_ERROR_NAMED( "RosBabelFish", "Failed to translate service response!" ); 163 | return false; 164 | } 165 | return result; 166 | }, 167 | [ description ]() -> BabelFishMessage::Ptr 168 | { 169 | BabelFishMessage::Ptr message = boost::make_shared(); 170 | message->morph( description->request, description->md5 ); 171 | return message; 172 | }, 173 | [ description ]() -> BabelFishMessage::Ptr 174 | { 175 | BabelFishMessage::Ptr message = boost::make_shared(); 176 | message->morph( description->response, description->md5 ); 177 | return message; 178 | } 179 | )); 180 | return nh.advertiseService( opts ); 181 | } 182 | 183 | Message::Ptr BabelFish::createMessage( const std::string &type ) 184 | { 185 | const MessageDescription::ConstPtr &description = description_provider_->getMessageDescription( type ); 186 | if ( description == nullptr ) 187 | { 188 | throw BabelFishException( "BabelFish doesn't know a message of type: " + type ); 189 | } 190 | return std::make_shared( description->message_template ); 191 | } 192 | 193 | Message::Ptr BabelFish::createServiceRequest( const std::string &type ) 194 | { 195 | const ServiceDescription::ConstPtr &description = description_provider_->getServiceDescription( type ); 196 | if ( description == nullptr ) 197 | { 198 | throw BabelFishException( "BabelFish doesn't know a service of type: " + type ); 199 | } 200 | return std::make_shared( description->request->message_template ); 201 | } 202 | 203 | bool BabelFish::callService( const std::string &service, const Message::ConstPtr &req, TranslatedMessage::Ptr &res ) 204 | { 205 | const std::string &datatype = req->as().datatype(); 206 | if ( strcmp( datatype.c_str() + datatype.length() - 7, "Request" ) != 0 ) 207 | { 208 | throw BabelFishException( "BabelFish can't call a service with a message that is not a request! " 209 | "Message Type: " + datatype ); 210 | } 211 | const std::string &service_type = datatype.substr( 0, datatype.length() - 7 ); 212 | const ServiceDescription::ConstPtr &description = description_provider_->getServiceDescription( service_type ); 213 | if ( description == nullptr ) 214 | { 215 | throw BabelFishException( "BabelFish doesn't know a service of type: " + service_type ); 216 | } 217 | BabelFishMessage::Ptr request = translateMessage( req ); 218 | BabelFishMessage::Ptr response = boost::make_shared(); 219 | response->morph( description->response ); 220 | bool result = ros::service::call( service, *request, *response ); 221 | res = translateMessage( response ); 222 | return result; 223 | } 224 | 225 | DescriptionProvider::Ptr &BabelFish::descriptionProvider() 226 | { 227 | return description_provider_; 228 | } 229 | } 230 | -------------------------------------------------------------------------------- /ros_babel_fish/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5.1) 2 | project(ros_babel_fish VERSION 0.9.1) 3 | 4 | # If the value doesn't fit, an exception is thrown in any case because that could result in unexpected behavior and can not be ignored lightly 5 | option(WARN_ON_INCOMPATIBLE_TYPE "If ON a warning is printed if a value message is set or accessed with a type that does not allow casting without loss of information" ON) 6 | 7 | if (WARN_ON_INCOMPATIBLE_TYPE) 8 | add_definitions(-DRBF_WARN_ON_INCOMPATIBLE_TYPE) 9 | endif () 10 | 11 | ## Compile as C++11, supported in ROS Kinetic and newer 12 | add_compile_options(-std=c++11) 13 | 14 | add_definitions(-Wall -Wextra) 15 | 16 | #set(CMAKE_BUILD_TYPE "Debug") 17 | 18 | ## Find catkin macros and libraries 19 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) 20 | ## is used, also find other catkin packages 21 | find_package(catkin REQUIRED COMPONENTS actionlib roscpp roslib std_msgs) 22 | find_package(OpenSSL REQUIRED) 23 | 24 | ################################### 25 | ## catkin specific configuration ## 26 | ################################### 27 | ## The catkin_package macro generates cmake config files for your package 28 | ## Declare things to be passed to dependent projects 29 | ## INCLUDE_DIRS: uncomment this if your package contains header files 30 | ## LIBRARIES: libraries you create in this project that dependent projects also need 31 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 32 | ## DEPENDS: system dependencies of this project that dependent projects also need 33 | catkin_package( 34 | INCLUDE_DIRS include 35 | LIBRARIES ${PROJECT_NAME} 36 | CATKIN_DEPENDS actionlib roscpp roslib 37 | DEPENDS OPENSSL 38 | ) 39 | 40 | ########### 41 | ## Build ## 42 | ########### 43 | 44 | ## Specify additional locations of header files 45 | ## Your package locations should be listed before other locations 46 | include_directories( 47 | include 48 | ${catkin_INCLUDE_DIRS} 49 | ${OPENSSL_INCLUDE_DIR} 50 | ) 51 | 52 | set(LIBRARIES 53 | ${catkin_LIBRARIES} 54 | OpenSSL::SSL 55 | stdc++fs 56 | ) 57 | 58 | set(SOURCES 59 | src/generation/providers/integrated_description_provider.cpp 60 | src/generation/description_provider.cpp 61 | src/generation/message_creation.cpp 62 | src/messages/array_message.cpp 63 | src/messages/compound_message.cpp 64 | src/messages/value_message.cpp 65 | src/babel_fish.cpp 66 | src/babel_fish_message.cpp 67 | src/message.cpp 68 | src/message_extractor.cpp 69 | ) 70 | 71 | 72 | ## Declare a C++ library 73 | add_library(${PROJECT_NAME} ${SOURCES}) 74 | target_link_libraries(${PROJECT_NAME} ${LIBRARIES}) 75 | 76 | ## Declare examples as C++ executables 77 | add_executable(${PROJECT_NAME}_any_publisher examples/any_publisher.cpp) 78 | ## Specify libraries to link a library or executable target against 79 | target_link_libraries(${PROJECT_NAME}_any_publisher ${PROJECT_NAME} ${LIBRARIES}) 80 | set_target_properties(${PROJECT_NAME}_any_publisher PROPERTIES OUTPUT_NAME any_publisher PREFIX "") 81 | 82 | add_executable(${PROJECT_NAME}_any_subscriber examples/any_subscriber.cpp) 83 | target_link_libraries(${PROJECT_NAME}_any_subscriber ${PROJECT_NAME} ${LIBRARIES}) 84 | set_target_properties(${PROJECT_NAME}_any_subscriber PROPERTIES OUTPUT_NAME any_subscriber PREFIX "") 85 | 86 | add_executable(${PROJECT_NAME}_message_info examples/message_info.cpp) 87 | target_link_libraries(${PROJECT_NAME}_message_info ${PROJECT_NAME} ${LIBRARIES}) 88 | set_target_properties(${PROJECT_NAME}_message_info PROPERTIES OUTPUT_NAME message_info PREFIX "") 89 | 90 | add_executable(${PROJECT_NAME}_troll_node examples/troll_node.cpp) 91 | target_link_libraries(${PROJECT_NAME}_troll_node ${PROJECT_NAME} ${LIBRARIES}) 92 | set_target_properties(${PROJECT_NAME}_troll_node PROPERTIES OUTPUT_NAME troll_node PREFIX "") 93 | 94 | add_executable(${PROJECT_NAME}_service_info examples/service_info.cpp) 95 | target_link_libraries(${PROJECT_NAME}_service_info ${PROJECT_NAME} ${LIBRARIES}) 96 | set_target_properties(${PROJECT_NAME}_service_info PROPERTIES OUTPUT_NAME service_info PREFIX "") 97 | 98 | add_executable(${PROJECT_NAME}_service_server examples/service_server.cpp) 99 | target_link_libraries(${PROJECT_NAME}_service_server ${PROJECT_NAME} ${LIBRARIES}) 100 | set_target_properties(${PROJECT_NAME}_service_server PROPERTIES OUTPUT_NAME service_server PREFIX "") 101 | 102 | add_executable(${PROJECT_NAME}_service_client examples/service_client.cpp) 103 | target_link_libraries(${PROJECT_NAME}_service_client ${PROJECT_NAME} ${LIBRARIES}) 104 | set_target_properties(${PROJECT_NAME}_service_client PROPERTIES OUTPUT_NAME service_client PREFIX "") 105 | 106 | add_executable(${PROJECT_NAME}_action_client examples/action_client.cpp) 107 | target_link_libraries(${PROJECT_NAME}_action_client ${PROJECT_NAME} ${LIBRARIES}) 108 | set_target_properties(${PROJECT_NAME}_action_client PROPERTIES OUTPUT_NAME action_client PREFIX "") 109 | 110 | find_package(rosbag_storage QUIET) 111 | if (rosbag_storage_FOUND) 112 | include_directories(${rosbag_storage_INCLUDE_DIRS}) 113 | add_executable(${PROJECT_NAME}_rosbag examples/rosbag_frame_ids.cpp) 114 | target_link_libraries(${PROJECT_NAME}_rosbag ${PROJECT_NAME} ${LIBRARIES} ${rosbag_storage_LIBRARIES} ) 115 | set_target_properties(${PROJECT_NAME}_rosbag PROPERTIES OUTPUT_NAME rosbag_frame_ids PREFIX "") 116 | endif () 117 | 118 | 119 | ############# 120 | ## Install ## 121 | ############# 122 | 123 | # all install targets should use catkin DESTINATION variables 124 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 125 | 126 | ## Mark executables for installation 127 | ## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html 128 | install(TARGETS 129 | ${PROJECT_NAME}_action_client 130 | ${PROJECT_NAME}_any_publisher 131 | ${PROJECT_NAME}_any_subscriber 132 | ${PROJECT_NAME}_message_info 133 | ${PROJECT_NAME}_troll_node 134 | ${PROJECT_NAME}_service_info 135 | ${PROJECT_NAME}_service_server 136 | ${PROJECT_NAME}_service_client 137 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 138 | ) 139 | 140 | ## Mark libraries for installation 141 | install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) 142 | 143 | ## Mark cpp header files for installation 144 | install(DIRECTORY include/${PROJECT_NAME}/ 145 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 146 | FILES_MATCHING PATTERN "*.h" 147 | PATTERN ".svn" EXCLUDE 148 | ) 149 | 150 | 151 | ############# 152 | ## Testing ## 153 | ############# 154 | 155 | if (CATKIN_ENABLE_TESTING) 156 | find_package(rostest REQUIRED) 157 | find_package(rosapi REQUIRED) 158 | find_package(ros_babel_fish_test_msgs REQUIRED) 159 | include_directories(${ros_babel_fish_test_msgs_INCLUDE_DIRS} ${rosapi_INCLUDE_DIRS} ${rostest_INCLUDE_DIRS}) 160 | 161 | add_rostest_gtest(${PROJECT_NAME}_test_message test/test_message.test test/message.cpp) 162 | target_link_libraries(${PROJECT_NAME}_test_message ${PROJECT_NAME}) 163 | set_target_properties(${PROJECT_NAME}_test_message PROPERTIES OUTPUT_NAME test_message PREFIX "") 164 | 165 | add_rostest_gtest(${PROJECT_NAME}_test_message_decoding test/test_message_decoding.test test/message_decoding.cpp) 166 | target_link_libraries(${PROJECT_NAME}_test_message_decoding ${PROJECT_NAME} ${ros_babel_fish_test_msgs_LIBRARIES}) 167 | set_target_properties(${PROJECT_NAME}_test_message_decoding PROPERTIES OUTPUT_NAME test_message_decoding PREFIX "") 168 | 169 | add_rostest_gtest(${PROJECT_NAME}_test_message_encoding test/test_message_encoding.test test/message_encoding.cpp) 170 | target_link_libraries(${PROJECT_NAME}_test_message_encoding ${PROJECT_NAME} ${ros_babel_fish_test_msgs_LIBRARIES}) 171 | set_target_properties(${PROJECT_NAME}_test_message_encoding PROPERTIES OUTPUT_NAME test_message_encoding PREFIX "") 172 | 173 | add_rostest_gtest(${PROJECT_NAME}_test_message_extractor test/test_message_extractor.test test/message_extractor.cpp) 174 | target_link_libraries(${PROJECT_NAME}_test_message_extractor ${PROJECT_NAME} ${ros_babel_fish_test_msgs_LIBRARIES}) 175 | set_target_properties(${PROJECT_NAME}_test_message_extractor PROPERTIES OUTPUT_NAME test_message_extractor PREFIX "") 176 | 177 | add_rostest_gtest(${PROJECT_NAME}_test_message_lookup test/test_message_lookup.test test/message_lookup.cpp) 178 | target_link_libraries(${PROJECT_NAME}_test_message_lookup ${PROJECT_NAME} ${ros_babel_fish_test_msgs_LIBRARIES}) 179 | set_target_properties(${PROJECT_NAME}_test_message_lookup PROPERTIES OUTPUT_NAME test_message_lookup PREFIX "") 180 | 181 | add_rostest_gtest(${PROJECT_NAME}_test_service_lookup test/test_service_lookup.test test/service_lookup.cpp) 182 | target_link_libraries(${PROJECT_NAME}_test_service_lookup ${PROJECT_NAME} ${ros_babel_fish_test_msgs_LIBRARIES}) 183 | set_target_properties(${PROJECT_NAME}_test_service_lookup PROPERTIES OUTPUT_NAME test_service_lookup PREFIX "") 184 | 185 | add_rostest_gtest(${PROJECT_NAME}_test_service_client test/test_service_client.test test/service_client.cpp) 186 | target_link_libraries(${PROJECT_NAME}_test_service_client ${PROJECT_NAME}) 187 | set_target_properties(${PROJECT_NAME}_test_service_client PROPERTIES OUTPUT_NAME test_service_client PREFIX "") 188 | 189 | add_executable(${PROJECT_NAME}_test_service_client_services test/service_client_test_services.cpp) 190 | target_link_libraries(${PROJECT_NAME}_test_service_client_services ${PROJECT_NAME}) 191 | set_target_properties(${PROJECT_NAME}_test_service_client_services PROPERTIES OUTPUT_NAME test_service_client_services PREFIX "") 192 | 193 | add_rostest_gtest(${PROJECT_NAME}_test_action_client test/test_action_client.test test/action_client.cpp) 194 | target_link_libraries(${PROJECT_NAME}_test_action_client ${PROJECT_NAME}) 195 | set_target_properties(${PROJECT_NAME}_test_action_client PROPERTIES OUTPUT_NAME test_action_client PREFIX "") 196 | 197 | add_executable(${PROJECT_NAME}_test_action_client_test_server test/action_client_test_server.cpp) 198 | target_link_libraries(${PROJECT_NAME}_test_action_client_test_server ${PROJECT_NAME}) 199 | set_target_properties(${PROJECT_NAME}_test_action_client_test_server PROPERTIES OUTPUT_NAME test_action_client_test_server PREFIX "") 200 | endif () 201 | 202 | # to run: catkin build ros_babel_fish --no-deps -DENABLE_COVERAGE_TESTING=ON -DCMAKE_BUILD_TYPE=Debug -v --catkin-make-args ros_babel_fish_coverage 203 | # Path to results overview will be printed in the build process 204 | # Big thanks to the moveit people from whose docs I've obtained the information and code to get the coverage 205 | # Note: Sometimes this command has to be run twice. Don't know why. If you do, please tell me! 206 | if(CATKIN_ENABLE_TESTING AND ENABLE_COVERAGE_TESTING) 207 | find_package(code_coverage REQUIRED) # catkin package ros-*-code-coverage 208 | include(CodeCoverage) 209 | append_coverage_compiler_flags() 210 | set(COVERAGE_EXCLUDES "*/${PROJECT_NAME}/test*" "*/${PROJECT_NAME}/examples*" "*/${PROJECT_NAME}/benchmarks*") 211 | add_code_coverage(NAME ${PROJECT_NAME}_coverage) 212 | endif () 213 | -------------------------------------------------------------------------------- /ros_babel_fish/src/message.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2019 Stefan Fabian. All rights reserved. 2 | // Licensed under the MIT license. See LICENSE file in the project root for full license information. 3 | 4 | #include "ros_babel_fish/message.h" 5 | #include "ros_babel_fish/messages/internal/value_compatibility.h" 6 | #include "ros_babel_fish/messages/compound_message.h" 7 | #include "ros_babel_fish/messages/value_message.h" 8 | #include "ros_babel_fish/babel_fish.h" 9 | 10 | 11 | namespace ros_babel_fish 12 | { 13 | 14 | Message::Message( MessageType type, const uint8_t *stream ) : type_( type ), stream_( stream ) { } 15 | 16 | Message &Message::operator[]( const std::string & ) 17 | { 18 | throw BabelFishException( 19 | "Tried to access child message on message object that does not support child access by key." ); 20 | } 21 | 22 | const Message &Message::operator[]( const std::string & ) const 23 | { 24 | throw BabelFishException( 25 | "Tried to access child message on message object that does not support child access by key." ); 26 | } 27 | 28 | Message::~Message() = default; 29 | 30 | namespace 31 | { 32 | 33 | template 34 | void assignValue( Message *m, const T &value ) 35 | { 36 | using namespace message_type_traits; 37 | if ( !internal::isCompatible()) 38 | { 39 | if ( !internal::inBounds( value )) 40 | { 41 | throw BabelFishException( 42 | "Value does not fit into value message! Make sure you're using the correct type or at least stay within the range of values for the message type!" ); 43 | } 44 | #if RBF_WARN_ON_INCOMPATIBLE_TYPE 45 | ROS_WARN_ONCE_NAMED( "RosBabelFish", 46 | "Assigned value fits but the type of the assignment can not be converted without loss of information in some cases! This message is printed only once!" ); 47 | #endif 48 | } 49 | m->as>().setValue( static_cast(value)); 50 | } 51 | 52 | template 53 | void assignToValueMessage( Message *m, const T &value ) 54 | { 55 | using namespace message_type_traits; 56 | switch ( m->type()) 57 | { 58 | case MessageTypes::Bool: 59 | throw BabelFishException( "Can not assign non-boolean value to a boolean ValueMessage!" ); 60 | case MessageTypes::UInt8: 61 | assignValue::value>( m, value ); 62 | break; 63 | case MessageTypes::UInt16: 64 | assignValue::value>( m, value ); 65 | break; 66 | case MessageTypes::UInt32: 67 | assignValue::value>( m, value ); 68 | break; 69 | case MessageTypes::UInt64: 70 | assignValue::value>( m, value ); 71 | break; 72 | case MessageTypes::Int8: 73 | assignValue::value>( m, value ); 74 | break; 75 | case MessageTypes::Int16: 76 | assignValue::value>( m, value ); 77 | break; 78 | case MessageTypes::Int32: 79 | assignValue::value>( m, value ); 80 | break; 81 | case MessageTypes::Int64: 82 | assignValue::value>( m, value ); 83 | break; 84 | case MessageTypes::Float32: 85 | assignValue::value>( m, value ); 86 | break; 87 | case MessageTypes::Float64: 88 | assignValue::value>( m, value ); 89 | break; 90 | case MessageTypes::Duration: 91 | throw BabelFishException( "Can not assign non-duration value to a duration ValueMessage!" ); 92 | case MessageTypes::Time: 93 | throw BabelFishException( "Can not assign non-time value to a time ValueMessage!" ); 94 | case MessageTypes::String: 95 | throw BabelFishException( "Can not assign non-string value to a string ValueMessage!" ); 96 | default: 97 | throw BabelFishException( "Tried to assign value to Message that is not a ValueMessage!" ); 98 | } 99 | } 100 | } 101 | 102 | Message &Message::operator=( bool value ) 103 | { 104 | if ( type() != MessageTypes::Bool ) 105 | throw BabelFishException( "Can not assign a boolean to a non-boolean ValueMessage!" ); 106 | as>() = value; 107 | return *this; 108 | } 109 | 110 | Message &Message::operator=( uint8_t value ) 111 | { 112 | assignToValueMessage( this, value ); 113 | return *this; 114 | } 115 | 116 | Message &Message::operator=( uint16_t value ) 117 | { 118 | assignToValueMessage( this, value ); 119 | return *this; 120 | } 121 | 122 | Message &Message::operator=( uint32_t value ) 123 | { 124 | assignToValueMessage( this, value ); 125 | return *this; 126 | } 127 | 128 | Message &Message::operator=( uint64_t value ) 129 | { 130 | assignToValueMessage( this, value ); 131 | return *this; 132 | } 133 | 134 | Message &Message::operator=( int8_t value ) 135 | { 136 | assignToValueMessage( this, value ); 137 | return *this; 138 | } 139 | 140 | Message &Message::operator=( int16_t value ) 141 | { 142 | assignToValueMessage( this, value ); 143 | return *this; 144 | } 145 | 146 | Message &Message::operator=( int32_t value ) 147 | { 148 | assignToValueMessage( this, value ); 149 | return *this; 150 | } 151 | 152 | Message &Message::operator=( int64_t value ) 153 | { 154 | assignToValueMessage( this, value ); 155 | return *this; 156 | } 157 | 158 | Message &Message::operator=( float value ) 159 | { 160 | assignToValueMessage( this, value ); 161 | return *this; 162 | } 163 | 164 | Message &Message::operator=( double value ) 165 | { 166 | assignToValueMessage( this, value ); 167 | return *this; 168 | } 169 | 170 | Message &Message::operator=( const std::string &value ) 171 | { 172 | if ( type() != MessageTypes::String ) 173 | throw BabelFishException( "Can not assign a string to a non-string ValueMessage!" ); 174 | as>() = value; 175 | return *this; 176 | } 177 | 178 | Message &Message::operator=( const ros::Time &value ) 179 | { 180 | if ( type() != MessageTypes::Time ) 181 | throw BabelFishException( "Can not assign ros::Time to Message that is not ValueMessage!" ); 182 | as>() = value; 183 | return *this; 184 | } 185 | 186 | Message &Message::operator=( const ros::Duration &value ) 187 | { 188 | if ( type() != MessageTypes::Duration ) 189 | throw BabelFishException( "Can not assign ros::Duration to Message that is not ValueMessage!" ); 190 | as>() = value; 191 | return *this; 192 | } 193 | 194 | 195 | namespace 196 | { 197 | template 198 | U obtainValue( const Message *m ) 199 | { 200 | using namespace message_type_traits; 201 | T val = m->as>().getValue(); 202 | if ( !internal::isCompatible()) 203 | { 204 | if ( !internal::inBounds( val )) 205 | { 206 | throw BabelFishException( "Value does not fit into casted type!" ); 207 | } 208 | #if RBF_WARN_ON_INCOMPATIBLE_TYPE 209 | ROS_WARN_ONCE_NAMED( "RosBabelFish", 210 | "Value fits into casted type but it is smaller than the message type which may lead to catastrophic failure in the future! This message is printed only once!" ); 211 | #endif 212 | } 213 | return static_cast(val); 214 | } 215 | 216 | template 217 | T obtainValueAsType( const Message *m ) 218 | { 219 | using namespace message_type_traits; 220 | switch ( m->type()) 221 | { 222 | case MessageTypes::UInt8: 223 | return obtainValue::value, T>( m ); 224 | case MessageTypes::UInt16: 225 | return obtainValue::value, T>( m ); 226 | case MessageTypes::UInt32: 227 | return obtainValue::value, T>( m ); 228 | case MessageTypes::UInt64: 229 | return obtainValue::value, T>( m ); 230 | case MessageTypes::Int8: 231 | return obtainValue::value, T>( m ); 232 | case MessageTypes::Int16: 233 | return obtainValue::value, T>( m ); 234 | case MessageTypes::Int32: 235 | return obtainValue::value, T>( m ); 236 | case MessageTypes::Int64: 237 | return obtainValue::value, T>( m ); 238 | case MessageTypes::Float32: 239 | return obtainValue::value, T>( m ); 240 | case MessageTypes::Float64: 241 | return obtainValue::value, T>( m ); 242 | default: 243 | throw BabelFishException( "Tried to retrieve content of ValueMessage as incompatible type!" ); 244 | } 245 | } 246 | } 247 | 248 | template<> 249 | bool Message::value() const 250 | { 251 | if ( type() != MessageTypes::Bool ) 252 | throw BabelFishException( "Can not return value of non-boolean ValueMessage as boolean!" ); 253 | return as>().getValue(); 254 | } 255 | 256 | template<> 257 | uint8_t Message::value() const { return obtainValueAsType( this ); } 258 | 259 | template<> 260 | uint16_t Message::value() const { return obtainValueAsType( this ); } 261 | 262 | template<> 263 | uint32_t Message::value() const { return obtainValueAsType( this ); } 264 | 265 | template<> 266 | uint64_t Message::value() const { return obtainValueAsType( this ); } 267 | 268 | template<> 269 | int8_t Message::value() const { return obtainValueAsType( this ); } 270 | 271 | template<> 272 | int16_t Message::value() const { return obtainValueAsType( this ); } 273 | 274 | template<> 275 | int32_t Message::value() const { return obtainValueAsType( this ); } 276 | 277 | template<> 278 | int64_t Message::value() const { return obtainValueAsType( this ); } 279 | 280 | template<> 281 | float Message::value() const { return obtainValueAsType( this ); } 282 | 283 | template<> 284 | double Message::value() const { return obtainValueAsType( this ); } 285 | 286 | template<> 287 | std::string Message::value() const 288 | { 289 | if ( type() != MessageTypes::String ) 290 | throw BabelFishException( "Can not return value of non-string ValueMessage as string!" ); 291 | return as>().getValue(); 292 | } 293 | 294 | template<> 295 | ros::Time Message::value() const 296 | { 297 | if ( type() != MessageTypes::Time ) 298 | throw BabelFishException( "Can not return value of non-time ValueMessage as ros::Time!" ); 299 | return as>().getValue(); 300 | } 301 | 302 | template<> 303 | ros::Duration Message::value() const 304 | { 305 | if ( type() != MessageTypes::Duration ) 306 | throw BabelFishException( "Can not return value of non-duration ValueMessage as ros::Duration!" ); 307 | return as>().getValue(); 308 | } 309 | } 310 | --------------------------------------------------------------------------------