turtlebot3_drive.cpp
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 
20 
22  : nh_priv_("~")
23 {
24  //Init gazebo ros turtlebot3 node
25  ROS_INFO("TurtleBot3 Simulation Node Init");
26  auto ret = init();
27  ROS_ASSERT(ret);
28 }
29 
31 {
32  updatecommandVelocity(0.0, 0.0);
33  ros::shutdown();
34 }
35 
36 /*******************************************************************************
37 * Init function
38 *******************************************************************************/
40 {
41  // initialize ROS parameter
42  std::string cmd_vel_topic_name = nh_.param<std::string>("cmd_vel_topic_name", "");
43 
44  // initialize variables
45  escape_range_ = 30.0 * DEG2RAD;
46  check_forward_dist_ = 0.7;
47  check_side_dist_ = 0.6;
48 
49  tb3_pose_ = 0.0;
50  prev_tb3_pose_ = 0.0;
51 
52  // initialize publishers
53  cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>(cmd_vel_topic_name, 10);
54 
55  // initialize subscribers
58 
59  return true;
60 }
61 
62 void Turtlebot3Drive::odomMsgCallBack(const nav_msgs::Odometry::ConstPtr &msg)
63 {
64  double siny = 2.0 * (msg->pose.pose.orientation.w * msg->pose.pose.orientation.z + msg->pose.pose.orientation.x * msg->pose.pose.orientation.y);
65  double cosy = 1.0 - 2.0 * (msg->pose.pose.orientation.y * msg->pose.pose.orientation.y + msg->pose.pose.orientation.z * msg->pose.pose.orientation.z);
66 
67  tb3_pose_ = atan2(siny, cosy);
68 }
69 
70 void Turtlebot3Drive::laserScanMsgCallBack(const sensor_msgs::LaserScan::ConstPtr &msg)
71 {
72  uint16_t scan_angle[3] = {0, 30, 330};
73 
74  for (int num = 0; num < 3; num++)
75  {
76  if (std::isinf(msg->ranges.at(scan_angle[num])))
77  {
78  scan_data_[num] = msg->range_max;
79  }
80  else
81  {
82  scan_data_[num] = msg->ranges.at(scan_angle[num]);
83  }
84  }
85 }
86 
87 void Turtlebot3Drive::updatecommandVelocity(double linear, double angular)
88 {
89  geometry_msgs::Twist cmd_vel;
90 
91  cmd_vel.linear.x = linear;
92  cmd_vel.angular.z = angular;
93 
94  cmd_vel_pub_.publish(cmd_vel);
95 }
96 
97 /*******************************************************************************
98 * Control Loop function
99 *******************************************************************************/
101 {
102  static uint8_t turtlebot3_state_num = 0;
103 
104  switch(turtlebot3_state_num)
105  {
106  case GET_TB3_DIRECTION:
108  {
110  {
112  turtlebot3_state_num = TB3_RIGHT_TURN;
113  }
114  else if (scan_data_[RIGHT] < check_side_dist_)
115  {
117  turtlebot3_state_num = TB3_LEFT_TURN;
118  }
119  else
120  {
121  turtlebot3_state_num = TB3_DRIVE_FORWARD;
122  }
123  }
124 
126  {
128  turtlebot3_state_num = TB3_RIGHT_TURN;
129  }
130  break;
131 
132  case TB3_DRIVE_FORWARD:
134  turtlebot3_state_num = GET_TB3_DIRECTION;
135  break;
136 
137  case TB3_RIGHT_TURN:
138  if (fabs(prev_tb3_pose_ - tb3_pose_) >= escape_range_)
139  turtlebot3_state_num = GET_TB3_DIRECTION;
140  else
142  break;
143 
144  case TB3_LEFT_TURN:
145  if (fabs(prev_tb3_pose_ - tb3_pose_) >= escape_range_)
146  turtlebot3_state_num = GET_TB3_DIRECTION;
147  else
149  break;
150 
151  default:
152  turtlebot3_state_num = GET_TB3_DIRECTION;
153  break;
154  }
155 
156  return true;
157 }
158 
159 /*******************************************************************************
160 * Main function
161 *******************************************************************************/
162 int main(int argc, char* argv[])
163 {
164  ros::init(argc, argv, "turtlebot3_drive");
165  Turtlebot3Drive turtlebot3_drive;
166 
167  ros::Rate loop_rate(125);
168 
169  while (ros::ok())
170  {
171  turtlebot3_drive.controlLoop();
172  ros::spinOnce();
173  loop_rate.sleep();
174  }
175 
176  return 0;
177 }
Turtlebot3Drive::~Turtlebot3Drive
~Turtlebot3Drive()
Definition: turtlebot3_drive.cpp:30
GET_TB3_DIRECTION
#define GET_TB3_DIRECTION
Definition: turtlebot3_drive.h:38
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TB3_RIGHT_TURN
#define TB3_RIGHT_TURN
Definition: turtlebot3_drive.h:40
ANGULAR_VELOCITY
#define ANGULAR_VELOCITY
Definition: turtlebot3_drive.h:36
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
RIGHT
#define RIGHT
Definition: turtlebot3_drive.h:33
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::shutdown
ROSCPP_DECL void shutdown()
Turtlebot3Drive::init
bool init()
Definition: turtlebot3_drive.cpp:39
Turtlebot3Drive::cmd_vel_pub_
ros::Publisher cmd_vel_pub_
Definition: turtlebot3_drive.h:61
LINEAR_VELOCITY
#define LINEAR_VELOCITY
Definition: turtlebot3_drive.h:35
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
Turtlebot3Drive::tb3_pose_
double tb3_pose_
Definition: turtlebot3_drive.h:74
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
turtlebot3_drive.h
main
int main(int argc, char *argv[])
Definition: turtlebot3_drive.cpp:162
TB3_LEFT_TURN
#define TB3_LEFT_TURN
Definition: turtlebot3_drive.h:41
DEG2RAD
#define DEG2RAD
Definition: turtlebot3_drive.h:28
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
TB3_DRIVE_FORWARD
#define TB3_DRIVE_FORWARD
Definition: turtlebot3_drive.h:39
ros::Rate::sleep
bool sleep()
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::Turtlebot3Drive
Turtlebot3Drive()
Definition: turtlebot3_drive.cpp:21
LEFT
#define LEFT
Definition: turtlebot3_drive.h:32
CENTER
#define CENTER
Definition: turtlebot3_drive.h:31
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
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Rate
ROS_INFO
#define ROS_INFO(...)
ROS_ASSERT
#define ROS_ASSERT(cond)
Turtlebot3Drive::updatecommandVelocity
void updatecommandVelocity(double linear, double angular)
Definition: turtlebot3_drive.cpp:87
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