orientation_controller.h
Go to the documentation of this file.
1 //
2 // Created by bruce on 2021/5/19.
3 //
4 
5 #pragma once
6 
12 #include <sensor_msgs/Imu.h>
13 
15 {
16 class Controller : public controller_interface::MultiInterfaceController<rm_control::RmImuSensorInterface,
17  rm_control::RobotStateInterface>
18 {
19 public:
20  Controller() = default;
21  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
22  void update(const ros::Time& time, const ros::Duration& period) override;
23 
24 private:
25  bool getTransform(const ros::Time& time, geometry_msgs::TransformStamped& source2target, const double x,
26  const double y, const double z, const double w);
27  void imuDataCallback(const sensor_msgs::Imu::ConstPtr& msg);
28 
31 
33 
35  geometry_msgs::TransformStamped source2target_msg_;
36 
37  std::string frame_source_;
38  std::string frame_target_;
39 
41  bool receive_imu_msg_ = false;
42 };
43 } // namespace rm_orientation_controller
rm_common::TfRtBroadcaster
rm_orientation_controller::Controller::imu_sensor_
rm_control::RmImuSensorHandle imu_sensor_
Definition: orientation_controller.h:29
rm_orientation_controller::Controller::last_imu_update_time_
ros::Time last_imu_update_time_
Definition: orientation_controller.h:32
rm_orientation_controller::Controller::getTransform
bool getTransform(const ros::Time &time, geometry_msgs::TransformStamped &source2target, const double x, const double y, const double z, const double w)
Definition: orientation_controller.cpp:53
rm_orientation_controller::Controller::imu_data_sub_
ros::Subscriber imu_data_sub_
Definition: orientation_controller.h:40
rm_orientation_controller::Controller::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: orientation_controller.cpp:32
rm_control::RobotStateHandle
rm_orientation_controller::Controller::imuDataCallback
void imuDataCallback(const sensor_msgs::Imu::ConstPtr &msg)
Definition: orientation_controller.cpp:82
rm_imu_sensor_interface.h
rm_orientation_controller::Controller::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: orientation_controller.cpp:12
rm_control::RmImuSensorHandle
controller.h
hardware_interface::RobotHW
rm_orientation_controller::Controller::robot_state_
rm_control::RobotStateHandle robot_state_
Definition: orientation_controller.h:30
controller_interface::MultiInterfaceController
rm_orientation_controller
Definition: orientation_controller.h:14
rm_orientation_controller::Controller::receive_imu_msg_
bool receive_imu_msg_
Definition: orientation_controller.h:41
robot_state_interface.h
ros::Time
rm_orientation_controller::Controller::frame_target_
std::string frame_target_
Definition: orientation_controller.h:38
rm_orientation_controller::Controller::Controller
Controller()=default
tf2_geometry_msgs.h
rm_orientation_controller::Controller::source2target_msg_
geometry_msgs::TransformStamped source2target_msg_
Definition: orientation_controller.h:35
ros::Duration
rm_orientation_controller::Controller::tf_broadcaster_
rm_common::TfRtBroadcaster tf_broadcaster_
Definition: orientation_controller.h:34
rm_orientation_controller::Controller
Definition: orientation_controller.h:16
rm_orientation_controller::Controller::frame_source_
std::string frame_source_
Definition: orientation_controller.h:37
ros::NodeHandle
ros::Subscriber
multi_interface_controller.h


rm_orientation_controller
Author(s): Qiayuan Liao
autogenerated on Sun Apr 13 2025 02:56:32