.. _program_listing_file__tmp_ws_src_rcss3d_nao_include_rcss3d_nao_rcss3d_nao_node.hpp: Program Listing for File rcss3d_nao_node.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rcss3d_nao/include/rcss3d_nao/rcss3d_nao_node.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2022 Kenji Brameld // // 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 RCSS3D_NAO__RCSS3D_NAO_NODE_HPP_ #define RCSS3D_NAO__RCSS3D_NAO_NODE_HPP_ #include #include #include #include "rclcpp/node.hpp" #include "nao_lola_command_msgs/msg/joint_positions.hpp" #include "nao_lola_sensor_msgs/msg/accelerometer.hpp" #include "nao_lola_sensor_msgs/msg/angle.hpp" #include "nao_lola_sensor_msgs/msg/fsr.hpp" #include "nao_lola_sensor_msgs/msg/gyroscope.hpp" #include "nao_lola_sensor_msgs/msg/joint_positions.hpp" #include "rcss3d_agent_msgs/msg/percept.hpp" #include "rcss3d_agent_msgs/msg/beam.hpp" #include "sensor_msgs/msg/imu.hpp" #include "sensor_msgs/msg/joint_state.hpp" #include "soccer_vision_3d_msgs/msg/ball_array.hpp" #include "soccer_vision_3d_msgs/msg/goalpost_array.hpp" #include "soccer_vision_3d_msgs/msg/marking_array.hpp" #include "soccer_vision_3d_msgs/msg/robot_array.hpp" // Forward Declaration namespace rcss3d_agent { class Rcss3dAgent; class Params; } namespace rcss3d_nao { class ComplementaryFilter; class NaoJointsPid; } namespace rcss3d_nao { class Rcss3dNaoNode : public rclcpp::Node { public: explicit Rcss3dNaoNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions{}); virtual ~Rcss3dNaoNode(); private: std::unique_ptr params; std::unique_ptr rcss3dAgent; std::unique_ptr complementaryFilter; std::unique_ptr naoJointsPid; rclcpp::Publisher::SharedPtr accelerometerPub; rclcpp::Publisher::SharedPtr anglePub; rclcpp::Publisher::SharedPtr fsrPub; rclcpp::Publisher::SharedPtr gyroscopePub; rclcpp::Publisher::SharedPtr jointPositionsPub; rclcpp::Publisher::SharedPtr ballArrayPub; rclcpp::Publisher::SharedPtr goalpostArrayPub; rclcpp::Publisher::SharedPtr markingArrayPub; rclcpp::Publisher::SharedPtr robotArrayPub; rclcpp::Publisher::SharedPtr imuPub; rclcpp::Publisher::SharedPtr jointStatesPub; rclcpp::Subscription::SharedPtr jointPositionsSub; rclcpp::Subscription::SharedPtr beamSub; void perceptCallback(const rcss3d_agent_msgs::msg::Percept & percept); void beamToInitialPose(double x, double y, double theta); bool publishImu; bool publishJointStates; }; } // namespace rcss3d_nao #endif // RCSS3D_NAO__RCSS3D_NAO_NODE_HPP_