turtlebot3_fake.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: Yoonseok Pyo */
18 
19 #ifndef TURTLEBOT3_FAKE_H_
20 #define TURTLEBOT3_FAKE_H_
21 
22 #include <math.h>
23 
24 #include <ros/ros.h>
25 #include <ros/time.h>
26 #include <std_msgs/Int32.h>
27 #include <sensor_msgs/Imu.h>
28 #include <sensor_msgs/JointState.h>
29 #include <geometry_msgs/Vector3.h>
30 #include <geometry_msgs/Twist.h>
31 #include <tf/tf.h>
33 #include <nav_msgs/Odometry.h>
34 
35 #include <turtlebot3_msgs/SensorState.h>
36 
37 #include "turtlebot3_fake.h"
38 
39 #define WHEEL_RADIUS 0.033 // meter
40 
41 #define LEFT 0
42 #define RIGHT 1
43 
44 #define MAX_LINEAR_VELOCITY 0.22 // m/s
45 #define MAX_ANGULAR_VELOCITY 2.84 // rad/s
46 #define VELOCITY_STEP 0.01 // m/s
47 #define VELOCITY_LINEAR_X 0.01 // m/s
48 #define VELOCITY_ANGULAR_Z 0.1 // rad/s
49 #define SCALE_VELOCITY_LINEAR_X 1
50 #define SCALE_VELOCITY_ANGULAR_Z 1
51 
52 #define DEG2RAD(x) (x * 0.01745329252) // *PI/180
53 #define RAD2DEG(x) (x * 57.2957795131) // *180/PI
54 
55 #define TORQUE_ENABLE 1 // Value for enabling the torque of motor
56 #define TORQUE_DISABLE 0 // Value for disabling the torque of motor
57 
59 {
60  public:
63  bool init();
64  bool update();
65 
66  private:
67  // ROS NodeHandle
70 
71  // ROS Parameters
72  // (TODO)
73 
74  // ROS Time
77 
78  // ROS Topic Publishers
81 
82  // ROS Topic Subscribers
84 
85  sensor_msgs::JointState joint_states_;
86  nav_msgs::Odometry odom_;
88 
89  double wheel_speed_cmd_[2];
93 
94  float odom_pose_[3];
95  float odom_vel_[3];
96  double pose_cov_[36];
97 
98  std::string joint_states_name_[2];
99 
100  double last_position_[2];
101  double last_velocity_[2];
102 
106 
107  // Function prototypes
108  void commandVelocityCallback(const geometry_msgs::TwistConstPtr cmd_vel_msg);
109  bool updateOdometry(ros::Duration diff_time);
110  void updateJoint(void);
111  void updateTF(geometry_msgs::TransformStamped& odom_tf);
112 };
113 
114 #endif // TURTLEBOT3_FAKE_H_
Turtlebot3Fake::joint_states_name_
std::string joint_states_name_[2]
Definition: turtlebot3_fake.h:98
Turtlebot3Fake::joint_states_pub_
ros::Publisher joint_states_pub_
Definition: turtlebot3_fake.h:79
Turtlebot3Fake::odom_pub_
ros::Publisher odom_pub_
Definition: turtlebot3_fake.h:80
ros::Publisher
Turtlebot3Fake::init
bool init()
Definition: turtlebot3_fake.cpp:36
Turtlebot3Fake::last_cmd_vel_time_
ros::Time last_cmd_vel_time_
Definition: turtlebot3_fake.h:75
Turtlebot3Fake::turning_radius_
double turning_radius_
Definition: turtlebot3_fake.h:104
Turtlebot3Fake::odom_pose_
float odom_pose_[3]
Definition: turtlebot3_fake.h:94
ros.h
time.h
Turtlebot3Fake::last_position_
double last_position_[2]
Definition: turtlebot3_fake.h:100
Turtlebot3Fake::goal_linear_velocity_
double goal_linear_velocity_
Definition: turtlebot3_fake.h:90
turtlebot3_fake.h
Turtlebot3Fake::nh_
ros::NodeHandle nh_
Definition: turtlebot3_fake.h:68
Turtlebot3Fake::last_velocity_
double last_velocity_[2]
Definition: turtlebot3_fake.h:101
transform_broadcaster.h
Turtlebot3Fake::nh_priv_
ros::NodeHandle nh_priv_
Definition: turtlebot3_fake.h:69
Turtlebot3Fake::update
bool update()
Definition: turtlebot3_fake.cpp:209
Turtlebot3Fake::prev_update_time_
ros::Time prev_update_time_
Definition: turtlebot3_fake.h:76
Turtlebot3Fake::odom_vel_
float odom_vel_[3]
Definition: turtlebot3_fake.h:95
tf::TransformBroadcaster
Turtlebot3Fake::updateJoint
void updateJoint(void)
Definition: turtlebot3_fake.cpp:185
Turtlebot3Fake::wheel_speed_cmd_
double wheel_speed_cmd_[2]
Definition: turtlebot3_fake.h:89
Turtlebot3Fake::updateOdometry
bool updateOdometry(ros::Duration diff_time)
Definition: turtlebot3_fake.cpp:124
Turtlebot3Fake::pose_cov_
double pose_cov_[36]
Definition: turtlebot3_fake.h:96
Turtlebot3Fake::~Turtlebot3Fake
~Turtlebot3Fake()
Definition: turtlebot3_fake.cpp:29
Turtlebot3Fake::odom_
nav_msgs::Odometry odom_
Definition: turtlebot3_fake.h:86
Turtlebot3Fake
Definition: turtlebot3_fake.h:58
tf.h
Turtlebot3Fake::commandVelocityCallback
void commandVelocityCallback(const geometry_msgs::TwistConstPtr cmd_vel_msg)
Definition: turtlebot3_fake.cpp:110
Turtlebot3Fake::updateTF
void updateTF(geometry_msgs::TransformStamped &odom_tf)
Definition: turtlebot3_fake.cpp:196
ros::Time
Turtlebot3Fake::wheel_seperation_
double wheel_seperation_
Definition: turtlebot3_fake.h:103
Turtlebot3Fake::cmd_vel_sub_
ros::Subscriber cmd_vel_sub_
Definition: turtlebot3_fake.h:83
Turtlebot3Fake::tf_broadcaster_
tf::TransformBroadcaster tf_broadcaster_
Definition: turtlebot3_fake.h:87
Turtlebot3Fake::robot_radius_
double robot_radius_
Definition: turtlebot3_fake.h:105
Turtlebot3Fake::cmd_vel_timeout_
double cmd_vel_timeout_
Definition: turtlebot3_fake.h:92
Turtlebot3Fake::goal_angular_velocity_
double goal_angular_velocity_
Definition: turtlebot3_fake.h:91
Turtlebot3Fake::joint_states_
sensor_msgs::JointState joint_states_
Definition: turtlebot3_fake.h:85
ros::Duration
Turtlebot3Fake::Turtlebot3Fake
Turtlebot3Fake()
Definition: turtlebot3_fake.cpp:21
ros::NodeHandle
ros::Subscriber


turtlebot3_fake
Author(s): Pyo , Darby Lim
autogenerated on Wed Mar 2 2022 01:10:17