.. _program_listing_file__tmp_ws_src_turtlebot3_turtlebot3_node_include_turtlebot3_node_odometry.hpp: Program Listing for File odometry.hpp ===================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/turtlebot3/turtlebot3_node/include/turtlebot3_node/odometry.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2019 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. // // Author: Darby Lim #ifndef TURTLEBOT3_NODE__ODOMETRY_HPP_ #define TURTLEBOT3_NODE__ODOMETRY_HPP_ #include #include #include #include #include #include #include #include #include #include #include #include #include #include namespace robotis { namespace turtlebot3 { class Odometry { public: explicit Odometry( std::shared_ptr & nh, const double wheels_separation, const double wheels_radius); virtual ~Odometry() {} private: bool calculate_odometry(const rclcpp::Duration & duration); void update_imu(const std::shared_ptr & imu); void update_joint_state(const std::shared_ptr & joint_state); void joint_state_callback(const sensor_msgs::msg::JointState::SharedPtr joint_state_msg); void joint_state_and_imu_callback( const std::shared_ptr & joint_state_msg, const std::shared_ptr & imu_msg); void publish(const rclcpp::Time & now); std::shared_ptr nh_; std::unique_ptr tf_broadcaster_; rclcpp::Publisher::SharedPtr odom_pub_; rclcpp::Subscription::SharedPtr joint_state_sub_; std::shared_ptr< message_filters::Subscriber> msg_ftr_joint_state_sub_; std::shared_ptr> msg_ftr_imu_sub_; typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::JointState, sensor_msgs::msg::Imu> SyncPolicyJointStateImu; typedef message_filters::Synchronizer SynchronizerJointStateImu; std::shared_ptr joint_state_imu_sync_; double wheels_separation_; double wheels_radius_; std::string frame_id_of_odometry_; std::string child_frame_id_of_odometry_; bool use_imu_; bool publish_tf_; std::array diff_joint_positions_; double imu_angle_; std::array robot_pose_; std::array robot_vel_; }; } // namespace turtlebot3 } // namespace robotis #endif // TURTLEBOT3_NODE__ODOMETRY_HPP_