Program Listing for File odometry_2d_publisher.hpp
↰ Return to documentation for file (/tmp/ws/src/fuse/fuse_models/include/fuse_models/odometry_2d_publisher.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2019, Locus Robotics
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef FUSE_MODELS__ODOMETRY_2D_PUBLISHER_HPP_
#define FUSE_MODELS__ODOMETRY_2D_PUBLISHER_HPP_
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_ros/transform_listener.h>
#include <memory>
#include <mutex>
#include <string>
#include <fuse_models/parameters/odometry_2d_publisher_params.hpp>
#include <fuse_core/async_publisher.hpp>
#include <fuse_core/console.hpp>
#include <fuse_core/graph.hpp>
#include <fuse_core/transaction.hpp>
#include <fuse_core/uuid.hpp>
#include <fuse_core/variable.hpp>
#include <fuse_publishers/stamped_variable_synchronizer.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
namespace fuse_models
{
class Odometry2DPublisher : public fuse_core::AsyncPublisher
{
public:
FUSE_SMART_PTR_DEFINITIONS_WITH_EIGEN(Odometry2DPublisher)
using ParameterType = parameters::Odometry2DPublisherParams;
Odometry2DPublisher();
virtual ~Odometry2DPublisher() = default;
void initialize(
fuse_core::node_interfaces::NodeInterfaces<ALL_FUSE_CORE_NODE_INTERFACES> interfaces,
const std::string & name) override;
protected:
void onInit() override;
void notifyCallback(
fuse_core::Transaction::ConstSharedPtr transaction,
fuse_core::Graph::ConstSharedPtr graph) override;
void onStart() override;
void onStop() override;
bool getState(
const fuse_core::Graph & graph,
const rclcpp::Time & stamp,
const fuse_core::UUID & device_id,
fuse_core::UUID & position_uuid,
fuse_core::UUID & orientation_uuid,
fuse_core::UUID & velocity_linear_uuid,
fuse_core::UUID & velocity_angular_uuid,
fuse_core::UUID & acceleration_linear_uuid,
nav_msgs::msg::Odometry & odometry,
geometry_msgs::msg::AccelWithCovarianceStamped & acceleration);
void publishTimerCallback();
using Synchronizer = fuse_publishers::StampedVariableSynchronizer<
fuse_variables::Orientation2DStamped,
fuse_variables::Position2DStamped,
fuse_variables::VelocityLinear2DStamped,
fuse_variables::VelocityAngular2DStamped,
fuse_variables::AccelerationLinear2DStamped>;
fuse_core::node_interfaces::NodeInterfaces<
fuse_core::node_interfaces::Base,
fuse_core::node_interfaces::Clock,
fuse_core::node_interfaces::Logging,
fuse_core::node_interfaces::Parameters,
fuse_core::node_interfaces::Timers,
fuse_core::node_interfaces::Topics,
fuse_core::node_interfaces::Waitables
> interfaces_;
fuse_core::UUID device_id_;
rclcpp::Clock::SharedPtr clock_;
rclcpp::Logger logger_;
ParameterType params_;
rclcpp::Time latest_stamp_;
rclcpp::Time latest_covariance_stamp_;
bool latest_covariance_valid_{false};
nav_msgs::msg::Odometry odom_output_;
geometry_msgs::msg::AccelWithCovarianceStamped acceleration_output_;
Synchronizer synchronizer_;
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_pub_;
rclcpp::Publisher<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr acceleration_pub_;
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_ = nullptr;
std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
fuse_core::DelayedThrottleFilter delayed_throttle_filter_{10.0};
rclcpp::TimerBase::SharedPtr publish_timer_;
std::mutex mutex_;
};
} // namespace fuse_models
#endif // FUSE_MODELS__ODOMETRY_2D_PUBLISHER_HPP_