turtlebot3_drive.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2016 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Taehun Lim (Darby) */
18 
19 #ifndef TURTLEBOT3_DRIVE_H_
20 #define TURTLEBOT3_DRIVE_H_
21 
22 #include <ros/ros.h>
23 
24 #include <sensor_msgs/LaserScan.h>
25 #include <geometry_msgs/Twist.h>
26 #include <nav_msgs/Odometry.h>
27 
28 #define DEG2RAD (M_PI / 180.0)
29 #define RAD2DEG (180.0 / M_PI)
30 
31 #define CENTER 0
32 #define LEFT 1
33 #define RIGHT 2
34 
35 #define LINEAR_VELOCITY 0.3
36 #define ANGULAR_VELOCITY 1.5
37 
38 #define GET_TB3_DIRECTION 0
39 #define TB3_DRIVE_FORWARD 1
40 #define TB3_RIGHT_TURN 2
41 #define TB3_LEFT_TURN 3
42 
44 {
45  public:
48  bool init();
49  bool controlLoop();
50 
51  private:
52  // ROS NodeHandle
55 
56  // ROS Parameters
57 
58  // ROS Time
59 
60  // ROS Topic Publishers
62 
63  // ROS Topic Subscribers
66 
67  // Variables
68  double escape_range_;
71 
72  double scan_data_[3] = {0.0, 0.0, 0.0};
73 
74  double tb3_pose_;
76 
77  // Function prototypes
78  void updatecommandVelocity(double linear, double angular);
79  void laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg);
80  void odomMsgCallBack(const nav_msgs::Odometry::ConstPtr &msg);
81 };
82 #endif // TURTLEBOT3_DRIVE_H_
void laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg)
ros::NodeHandle nh_
double check_forward_dist_
double scan_data_[3]
ros::Publisher cmd_vel_pub_
ros::NodeHandle nh_priv_
void odomMsgCallBack(const nav_msgs::Odometry::ConstPtr &msg)
void updatecommandVelocity(double linear, double angular)
ros::Subscriber odom_sub_
ros::Subscriber laser_scan_sub_


turtlebot3_gazebo
Author(s): Pyo , Darby Lim , Gilbert
autogenerated on Sat Jan 16 2021 03:56:04