ros2_control - rolling
Loading...
Searching...
No Matches
imu_sensor_broadcaster.hpp
1// Copyright 2021 PAL Robotics SL.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*
16 * Authors: Subhas Das, Denis Stogl, Victor Lopez
17 */
18
19#ifndef IMU_SENSOR_BROADCASTER__IMU_SENSOR_BROADCASTER_HPP_
20#define IMU_SENSOR_BROADCASTER__IMU_SENSOR_BROADCASTER_HPP_
21
22#include <memory>
23#include <vector>
24
25#include "Eigen/Dense"
26#include "rclcpp_lifecycle/state.hpp"
27#include "realtime_tools/realtime_publisher.hpp"
28#include "semantic_components/imu_sensor.hpp"
29#include "sensor_msgs/msg/imu.hpp"
30
31#include "controller_interface/chainable_controller_interface.hpp"
32// auto-generated by generate_parameter_library
33#include "imu_sensor_broadcaster/imu_sensor_broadcaster_parameters.hpp"
34
35namespace imu_sensor_broadcaster
36{
38{
39public:
41
43 controller_interface::CallbackReturn on_init() override;
44
45 controller_interface::CallbackReturn on_configure(
46 const rclcpp_lifecycle::State & previous_state) override;
47
48 controller_interface::CallbackReturn on_activate(
49 const rclcpp_lifecycle::State & previous_state) override;
50
51 controller_interface::CallbackReturn on_deactivate(
52 const rclcpp_lifecycle::State & previous_state) override;
53
54 controller_interface::return_type update_and_write_commands(
55 const rclcpp::Time & time, const rclcpp::Duration & period) override;
56
57 controller_interface::return_type update_reference_from_subscribers(
58 const rclcpp::Time & time, const rclcpp::Duration & period) override;
59
60 std::vector<hardware_interface::StateInterface> on_export_state_interfaces() override;
61
62protected:
63 std::shared_ptr<ParamListener> param_listener_;
64 Params params_;
65 Eigen::Quaterniond r_;
66
67 std::unique_ptr<semantic_components::IMUSensor> imu_sensor_;
68
70 rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr sensor_state_publisher_;
71 std::unique_ptr<StatePublisher> realtime_publisher_;
72 sensor_msgs::msg::Imu state_message_;
73};
74
75} // namespace imu_sensor_broadcaster
76
77#endif // IMU_SENSOR_BROADCASTER__IMU_SENSOR_BROADCASTER_HPP_
Definition chainable_controller_interface.hpp:37
Definition imu_sensor_broadcaster.hpp:38
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition imu_sensor_broadcaster.cpp:93
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period) override
Update reference from input topics when not in chained mode.
Definition imu_sensor_broadcaster.cpp:140
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition imu_sensor_broadcaster.cpp:28
controller_interface::return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period) override
Execute calculations of the controller and update command interfaces.
Definition imu_sensor_broadcaster.cpp:124
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition imu_sensor_broadcaster.cpp:101
std::vector< hardware_interface::StateInterface > on_export_state_interfaces() override
Definition imu_sensor_broadcaster.cpp:146
Definition realtime_publisher.hpp:55
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:58