include
turtlebot3_gazebo
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
43
class
Turtlebot3Drive
44
{
45
public
:
46
Turtlebot3Drive
();
47
~Turtlebot3Drive
();
48
bool
init
();
49
bool
controlLoop
();
50
51
private
:
52
// ROS NodeHandle
53
ros::NodeHandle
nh_
;
54
ros::NodeHandle
nh_priv_
;
55
56
// ROS Parameters
57
58
// ROS Time
59
60
// ROS Topic Publishers
61
ros::Publisher
cmd_vel_pub_
;
62
63
// ROS Topic Subscribers
64
ros::Subscriber
laser_scan_sub_
;
65
ros::Subscriber
odom_sub_
;
66
67
// Variables
68
double
escape_range_
;
69
double
check_forward_dist_
;
70
double
check_side_dist_
;
71
72
double
scan_data_
[3] = {0.0, 0.0, 0.0};
73
74
double
tb3_pose_
;
75
double
prev_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_
Turtlebot3Drive::~Turtlebot3Drive
~Turtlebot3Drive()
Definition:
turtlebot3_drive.cpp:30
ros::Publisher
ros.h
Turtlebot3Drive::check_forward_dist_
double check_forward_dist_
Definition:
turtlebot3_drive.h:69
Turtlebot3Drive::check_side_dist_
double check_side_dist_
Definition:
turtlebot3_drive.h:70
Turtlebot3Drive::init
bool init()
Definition:
turtlebot3_drive.cpp:39
Turtlebot3Drive::cmd_vel_pub_
ros::Publisher cmd_vel_pub_
Definition:
turtlebot3_drive.h:61
Turtlebot3Drive::tb3_pose_
double tb3_pose_
Definition:
turtlebot3_drive.h:74
Turtlebot3Drive::scan_data_
double scan_data_[3]
Definition:
turtlebot3_drive.h:72
Turtlebot3Drive::nh_
ros::NodeHandle nh_
Definition:
turtlebot3_drive.h:53
Turtlebot3Drive
Definition:
turtlebot3_drive.h:43
Turtlebot3Drive::escape_range_
double escape_range_
Definition:
turtlebot3_drive.h:68
Turtlebot3Drive::laserScanMsgCallBack
void laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg)
Definition:
turtlebot3_drive.cpp:70
Turtlebot3Drive::nh_priv_
ros::NodeHandle nh_priv_
Definition:
turtlebot3_drive.h:54
Turtlebot3Drive::Turtlebot3Drive
Turtlebot3Drive()
Definition:
turtlebot3_drive.cpp:21
Turtlebot3Drive::laser_scan_sub_
ros::Subscriber laser_scan_sub_
Definition:
turtlebot3_drive.h:64
Turtlebot3Drive::controlLoop
bool controlLoop()
Definition:
turtlebot3_drive.cpp:100
Turtlebot3Drive::odomMsgCallBack
void odomMsgCallBack(const nav_msgs::Odometry::ConstPtr &msg)
Definition:
turtlebot3_drive.cpp:62
Turtlebot3Drive::prev_tb3_pose_
double prev_tb3_pose_
Definition:
turtlebot3_drive.h:75
Turtlebot3Drive::updatecommandVelocity
void updatecommandVelocity(double linear, double angular)
Definition:
turtlebot3_drive.cpp:87
ros::NodeHandle
ros::Subscriber
Turtlebot3Drive::odom_sub_
ros::Subscriber odom_sub_
Definition:
turtlebot3_drive.h:65
turtlebot3_gazebo
Author(s): Pyo
, Darby Lim
, Gilbert
autogenerated on Wed Mar 2 2022 01:10:20