.. _program_listing_file__tmp_ws_src_dynamixel_sdk_dynamixel_sdk_examples_include_read_write_node.hpp: Program Listing for File read_write_node.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/dynamixel_sdk/dynamixel_sdk_examples/include/read_write_node.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 ROBOTIS CO., LTD. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef READ_WRITE_NODE_HPP_ #define READ_WRITE_NODE_HPP_ #include #include #include #include "rclcpp/rclcpp.hpp" #include "rcutils/cmdline_parser.h" #include "dynamixel_sdk/dynamixel_sdk.h" #include "dynamixel_sdk_custom_interfaces/msg/set_position.hpp" #include "dynamixel_sdk_custom_interfaces/srv/get_position.hpp" class ReadWriteNode : public rclcpp::Node { public: using SetPosition = dynamixel_sdk_custom_interfaces::msg::SetPosition; using GetPosition = dynamixel_sdk_custom_interfaces::srv::GetPosition; ReadWriteNode(); virtual ~ReadWriteNode(); private: rclcpp::Subscription::SharedPtr set_position_subscriber_; rclcpp::Service::SharedPtr get_position_server_; int present_position; }; #endif // READ_WRITE_NODE_HPP_