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 #include <ros/time.h>
24 
25 #include <math.h>
26 #include <limits.h>
27 
28 #include <std_msgs/String.h>
29 #include <sensor_msgs/JointState.h>
30 #include <sensor_msgs/LaserScan.h>
31 #include <geometry_msgs/Twist.h>
32 #include <tf/tf.h>
33 #include <nav_msgs/Odometry.h>
34 
35 #define DEG2RAD (M_PI / 180.0)
36 #define RAD2DEG (180.0 / M_PI)
37 
38 #define CENTER 0
39 #define LEFT 1
40 #define RIGHT 2
41 
42 #define LINEAR_VELOCITY 0.3
43 #define ANGULAR_VELOCITY 1.5
44 
45 #define GET_TB3_DIRECTION 0
46 #define TB3_DRIVE_FORWARD 1
47 #define TB3_RIGHT_TURN 2
48 #define TB3_LEFT_TURN 3
49 
51 {
52  public:
55  bool init();
56  bool controlLoop();
57 
58  private:
59  // ROS NodeHandle
62 
63  // ROS Parameters
64  bool is_debug_;
65 
66  // ROS Time
67 
68  // ROS Topic Publishers
70 
71  // ROS Topic Subscribers
74 
76  double rotate_angle_;
79 
80  double direction_vector_[3] = {0.0, 0.0, 0.0};
81 
84 
85  // Function prototypes
86  void updatecommandVelocity(double linear, double angular);
87  void laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg);
88  void jointStateMsgCallBack(const sensor_msgs::JointState::ConstPtr &msg);
89 };
90 #endif // TURTLEBOT3_DRIVE_H_
void laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg)
double right_joint_encoder_
void jointStateMsgCallBack(const sensor_msgs::JointState::ConstPtr &msg)
ros::NodeHandle nh_
double front_distance_limit_
double direction_vector_[3]
ros::Publisher cmd_vel_pub_
ros::NodeHandle nh_priv_
double side_distance_limit_
ros::Subscriber joint_state_sub_
void updatecommandVelocity(double linear, double angular)
double priv_right_joint_encoder_
ros::Subscriber laser_scan_sub_


turtlebot3_gazebo_ros
Author(s): Pyo , Darby Lim
autogenerated on Fri Mar 16 2018 02:54:56