ls01b_node.h
Go to the documentation of this file.
1 /*******************************************************
2 @company: Copyright (C) 2018, Leishen Intelligent System
3 @product: LS01B
4 @filename: ls01b_node.h
5 @brief:
6 @version: date: author: comments:
7 @v1.0 18-8-28 fu new
8 *******************************************************/
9 #ifndef LS01B_NODE_H
10 #define LS01B_NODE_H
11 
12 #include <ros/ros.h>
13 #include <sensor_msgs/LaserScan.h>
14 #include "ls01b_v2/ls01b.h"
15 
16 namespace ls {
17 typedef struct{
18  double start;
19  double end;
21 
22 class LS01B_Node{
23 public:
24  LS01B_Node();
25  ~LS01B_Node();
26  void run();
27 
28 private:
29  void initParam();
30 
31  void publishScan(const ros::TimerEvent&);
32 
36 
38  std::string serial_port_;
41  std::string scan_topic_;
42  std::string frame_id_;
43 
45  double robot_radius_;
46  double center_x_;
47  double center_y_;
58 
60 };
61 }
62 
63 #endif // LS01B_NODE_H
Definition: ls01b.h:17
void publishScan(const ros::TimerEvent &)
Definition: ls01b_node.cpp:77
double angle_disable_max_3
Definition: ls01b_node.h:55
std::string frame_id_
Definition: ls01b_node.h:42
double angle_disable_min_0
Definition: ls01b_node.h:48
ros::Timer timer_
Definition: ls01b_node.h:35
DisableAngle dis_angle_[5]
Definition: ls01b_node.h:44
double center_y_
Definition: ls01b_node.h:47
std::string scan_topic_
Definition: ls01b_node.h:41
double angle_disable_min_4
Definition: ls01b_node.h:56
double angle_disable_min_2
Definition: ls01b_node.h:52
std::string serial_port_
Definition: ls01b_node.h:38
void initParam()
Definition: ls01b_node.cpp:32
double robot_radius_
Definition: ls01b_node.h:45
double angle_disable_max_2
Definition: ls01b_node.h:53
double center_x_
Definition: ls01b_node.h:46
double angle_resolution_
Definition: ls01b_node.h:40
double angle_disable_min_3
Definition: ls01b_node.h:54
double angle_disable_max_1
Definition: ls01b_node.h:51
double angle_disable_max_0
Definition: ls01b_node.h:49
ros::NodeHandle n_
Definition: ls01b_node.h:33
ros::Publisher pub_
Definition: ls01b_node.h:34
double angle_disable_max_4
Definition: ls01b_node.h:57
LS01B * ls01b_
Definition: ls01b_node.h:37
double angle_disable_min_1
Definition: ls01b_node.h:50
bool is_shuttdown_
Definition: ls01b_node.h:59


ls01b_v2
Author(s): fu
autogenerated on Sat Sep 28 2019 03:51:19