-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathunicycle_sim.cpp
More file actions
145 lines (105 loc) · 3.79 KB
/
unicycle_sim.cpp
File metadata and controls
145 lines (105 loc) · 3.79 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
#include <ros/ros.h>
#include <std_srvs/Empty.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include <tf/transform_broadcaster.h>
class Robot
{
public:
Robot(ros::NodeHandle &nh, double hz){
odom_pub_ = nh.advertise<nav_msgs::Odometry>("/odometry/filtered", 1);
cmd_vel_sub_ = nh.subscribe("cmd_vel", 1, &Robot::cmd_vel_callback, this);
dt_ = 1.0/hz;
state_ = {0.0, 0.0, 0.0};
desired_input_ = {0.0, 0.0};
max_v_ = 2.0;
max_w_ = 1.8;
is_paused = false;
// setup timer to run update_state at dt_
timer_ = nh.createTimer(ros::Duration(dt_), &Robot::update_state, this);
// ros service for resetting the robot
reset_srv_ = nh.advertiseService("reset", &Robot::reset_callback, this);
pause_srv_ = nh.advertiseService("pause", &Robot::pause_callback, this);
nh.param("unicycle_sim/x", state_[0], 0.0);
nh.param("unicycle_sim/y", state_[1], 0.0);
nh.param("unicycle_sim/yaw", state_[2], 0.0);
nh.param("unicycle_sim/frame_id", frame_id_, std::string("odom"));
nh.param("unicycle_sim/child_frame_id", child_frame_id_, std::string("base_link"));
}
void cmd_vel_callback(const geometry_msgs::Twist::ConstPtr& msg){
desired_input_ = {msg->linear.x, msg->angular.z};
desired_input_[0] = std::max(std::min(desired_input_[0], max_v_), -max_v_);
desired_input_[1] = std::max(std::min(desired_input_[1], max_w_), -max_w_);
}
void publishTrail(){
return;
}
bool reset_callback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res){
state_ = {0.0, 0.0, 0.0};
desired_input_ = {0.0, 0.0};
return true;
}
bool pause_callback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res){
is_paused = true;
return true;
}
void update_state(const ros::TimerEvent& event){
if (is_paused){
return;
}
// use discretized unicycle dynamics
double v0 = desired_input_[0];
double w0 = desired_input_[1];
if (fabs(w0) < 1e-6){
state_[0] = state_[0] + v0*dt_*cos(state_[2]);
state_[1] = state_[1] + v0*dt_*sin(state_[2]);
}
else{
state_[0] = state_[0] + (v0/w0)*(sin(state_[2] + w0*dt_) - sin(state_[2]));
state_[1] = state_[1] + (v0/w0)*(-cos(state_[2] + w0*dt_) + cos(state_[2]));
}
state_[2] = state_[2] + w0*dt_;
// publish odometry
nav_msgs::Odometry odom;
odom.header.stamp = ros::Time::now();
odom.header.frame_id = frame_id_;
odom.child_frame_id = "base_link";
odom.pose.pose.position.x = state_[0];
odom.pose.pose.position.y = state_[1];
odom.pose.pose.position.z = 0.0;
odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(state_[2]);
odom.twist.twist.linear.x = v0;
odom.twist.twist.angular.z = w0;
odom_pub_.publish(odom);
}
void spin(){
ros::AsyncSpinner spinner(1);
spinner.start();
ros::waitForShutdown();
}
bool initialized;
bool is_paused;
protected:
ros::NodeHandle nh_;
ros::Publisher odom_pub_;
ros::Publisher trail_pub_;
ros::Subscriber cmd_vel_sub_;
ros::ServiceServer reset_srv_;
ros::ServiceServer pause_srv_;
ros::Timer timer_;
std::vector<double> state_;
std::vector<double> desired_input_;
std::vector<std::tuple<double, double>> trail_;
double dt_;
double max_v_;
double max_w_;
std::string frame_id_;
std::string child_frame_id_;
};
int main(int argc, char** argv) {
ros::init(argc, argv, "unicycle_sim");
ros::NodeHandle nh;
Robot robot(nh, 50.);
robot.spin();
return 0;
}