tof_sensor_controller.h
Go to the documentation of this file.
1 //
2 // Created by luotinkai on 2022/1/2.
3 //
4 
5 #pragma once
6 
11 #include <rm_msgs/TofSensor.h>
12 
14 {
15 class Controller : public controller_interface::Controller<rm_control::TofSensorInterface>
16 {
17 public:
18  Controller() = default;
19 
20  bool init(rm_control::TofSensorInterface* hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
21 
22  void update(const ros::Time& time, const ros::Duration& period) override;
23 
24 private:
26  std::vector<rm_control::TofSensorHandle> tof_sensors_;
27  typedef std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::TofSensor>> RtpublisherPtr;
29  std::vector<RtpublisherPtr> realtime_pubs_;
30 };
31 } // namespace tof_sensor_controller
tof_sensor_controller::Controller::tof_pub_
RtpublisherPtr tof_pub_
Definition: tof_sensor_controller.h:28
realtime_publisher.h
tof_sensor_controller::Controller::tof_sensors_
std::vector< rm_control::TofSensorHandle > tof_sensors_
Definition: tof_sensor_controller.h:26
tof_sensor_controller
Definition: tof_sensor_controller.h:13
controller_interface::Controller
tof_sensor_controller::Controller::RtpublisherPtr
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::TofSensor > > RtpublisherPtr
Definition: tof_sensor_controller.h:27
tof_sensor_controller::Controller::Controller
Controller()=default
controller.h
tof_sensor_controller::Controller::init
bool init(rm_control::TofSensorInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: tof_sensor_controller.cpp:10
rm_control::TofSensorHandle
tof_sensor_controller::Controller::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: tof_sensor_controller.cpp:29
rm_control::TofSensorInterface
tof_sensor_controller::Controller
Definition: tof_sensor_controller.h:15
tof_sensor_controller::Controller::tof_sensor_handle
rm_control::TofSensorHandle tof_sensor_handle
Definition: tof_sensor_controller.h:25
ros::Time
tof_sensor_interface.h
tof_sensor_controller::Controller::realtime_pubs_
std::vector< RtpublisherPtr > realtime_pubs_
Definition: tof_sensor_controller.h:29
ros::Duration
ros::NodeHandle
multi_interface_controller.h


tof_sensor_controller
Author(s):
autogenerated on Fri Jun 10 2022 02:55:54