ros2_control - rolling
Loading...
Searching...
No Matches
joint_state_broadcaster.hpp
1// Copyright 2017 Open Source Robotics Foundation, Inc.
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#ifndef JOINT_STATE_BROADCASTER__JOINT_STATE_BROADCASTER_HPP_
16#define JOINT_STATE_BROADCASTER__JOINT_STATE_BROADCASTER_HPP_
17
18#include <memory>
19#include <string>
20#include <unordered_map>
21#include <vector>
22
23#include "control_msgs/msg/dynamic_joint_state.hpp"
24#include "controller_interface/controller_interface.hpp"
25#include "realtime_tools/realtime_publisher.hpp"
26#include "sensor_msgs/msg/joint_state.hpp"
27
28#include "rclcpp/version.h"
29// cppcheck-suppress syntaxError
30#if RCLCPP_VERSION_GTE(29, 0, 0)
31#include "urdf/model.hpp"
32#else
33#include "urdf/model.h"
34#endif
35
36// auto-generated by generate_parameter_library
37#include "joint_state_broadcaster/joint_state_broadcaster_parameters.hpp"
38
39namespace joint_state_broadcaster
40{
66{
67public:
69
71
73
74 controller_interface::return_type update(
75 const rclcpp::Time & time, const rclcpp::Duration & period) override;
76
77 controller_interface::CallbackReturn on_init() override;
78
79 controller_interface::CallbackReturn on_configure(
80 const rclcpp_lifecycle::State & previous_state) override;
81
82 controller_interface::CallbackReturn on_activate(
83 const rclcpp_lifecycle::State & previous_state) override;
84
85 controller_interface::CallbackReturn on_deactivate(
86 const rclcpp_lifecycle::State & previous_state) override;
87
88protected:
89 bool init_joint_data();
90 void init_auxiliary_data();
92 void init_dynamic_joint_state_msg();
93 bool use_all_available_interfaces() const;
94
95protected:
96 // Optional parameters
97 std::shared_ptr<ParamListener> param_listener_;
98 Params params_;
99 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
100
101 std::string frame_id_;
102
103 // For the JointState message,
104 // we store the name of joints with compatible interfaces
105 std::vector<std::string> joint_names_;
106 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
107 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
108 realtime_joint_state_publisher_;
109 sensor_msgs::msg::JointState joint_state_msg_;
110
111 // For the DynamicJointState format, we use a map to buffer values in for easier lookup
112 // This allows to preserve whatever order or names/interfaces were initialized.
113 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
114 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
115 dynamic_joint_state_publisher_;
116 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
117 realtime_dynamic_joint_state_publisher_;
118 control_msgs::msg::DynamicJointState dynamic_joint_state_msg_;
119
120 urdf::Model model_;
121 bool is_model_loaded_ = false;
122
123 std::vector<double *> mapped_values_;
124
126 {
127 JointStateData(const double & position, const double & velocity, const double & effort)
128 : position_(position), velocity_(velocity), effort_(effort)
129 {
130 }
131
132 const double & position_;
133 const double & velocity_;
134 const double & effort_;
135 };
136
137 std::vector<JointStateData> joint_states_data_;
138
139 std::vector<std::vector<const double *>> dynamic_joint_states_data_;
140};
141
142} // namespace joint_state_broadcaster
143
144#endif // JOINT_STATE_BROADCASTER__JOINT_STATE_BROADCASTER_HPP_
Definition controller_interface.hpp:27
Joint State Broadcaster for all or some state in a ros2_control system.
Definition joint_state_broadcaster.hpp:66
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition joint_state_broadcaster.cpp:66
controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition joint_state_broadcaster.cpp:440
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition joint_state_broadcaster.cpp:43
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition joint_state_broadcaster.cpp:60
void init_joint_state_msg()
Definition joint_state_broadcaster.cpp:359
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:69
Definition joint_state_broadcaster.hpp:126