Skip to content
Snippets Groups Projects
Commit d48a8361 authored by Jiaao Liu's avatar Jiaao Liu
Browse files

pwn change and meter information

parent c34e901e
Branches
No related tags found
No related merge requests found
...@@ -30,7 +30,7 @@ public: ...@@ -30,7 +30,7 @@ public:
}; };
PIDController pid(3, 0, 5); PIDController pid(30, 0, 5);
PIDController pid1(40, 0, 0); PIDController pid1(40, 0, 0);
PIDController pid_v(1.5, 0, 0); PIDController pid_v(1.5, 0, 0);
...@@ -49,7 +49,7 @@ float ref_w = 0; ...@@ -49,7 +49,7 @@ float ref_w = 0;
float w_now = 0; float w_now = 0;
float v_now = 0; float v_now = 0;
float initial_pwm = 25; float initial_pwm = 15;
//initial 26.5 //initial 26.5
void controlOperation(const geometry_msgs::Twist& msg) { void controlOperation(const geometry_msgs::Twist& msg) {
float flag; float flag;
...@@ -84,7 +84,7 @@ void pending(){ ...@@ -84,7 +84,7 @@ void pending(){
void pureRotation(float flag) { void pureRotation(float flag) {
float rotating_pwm = 15; float rotating_pwm = 10;
float right; float right;
float left; float left;
if (flag > 0) { if (flag > 0) {
......
...@@ -13,7 +13,7 @@ ros::Time time_previous, time_now; // Timing variables ...@@ -13,7 +13,7 @@ ros::Time time_previous, time_now; // Timing variables
ros::Duration elapsed_time; // Duration to calculate elapsed time ros::Duration elapsed_time; // Duration to calculate elapsed time
// Robot's position and orientation variables // Robot's position and orientation variables
float x = 0.0, y = 0.0, phi = 0.0; float x = 0.0, y = 0.0, phi = 0.0, S = 0.0;
double time_float; // Floating-point representation of elapsed time double time_float; // Floating-point representation of elapsed time
...@@ -76,7 +76,7 @@ void answer(const asclinic_pkg::LeftRightInt32& msg) { ...@@ -76,7 +76,7 @@ void answer(const asclinic_pkg::LeftRightInt32& msg) {
// Calculate the linear displacement and change in orientation // Calculate the linear displacement and change in orientation
float dS = (WHEEL_RADIUS_LEFT * deltaThetaL + WHEEL_RADIUS_RIGHT * deltaThetaR) / 2; float dS = (WHEEL_RADIUS_LEFT * deltaThetaL + WHEEL_RADIUS_RIGHT * deltaThetaR) / 2;
float dPhi = (WHEEL_RADIUS_RIGHT * deltaThetaR - WHEEL_RADIUS_LEFT * deltaThetaL) / (2 * HALF_WHEEL_BASE); float dPhi = (WHEEL_RADIUS_RIGHT * deltaThetaR - WHEEL_RADIUS_LEFT * deltaThetaL) / (2 * HALF_WHEEL_BASE);
S += abs(dS);
// Update position and orientation based on movements // Update position and orientation based on movements
x += dS * cos(phi + 0.5 * dPhi); x += dS * cos(phi + 0.5 * dPhi);
y += dS * sin(phi + 0.5 * dPhi); y += dS * sin(phi + 0.5 * dPhi);
...@@ -107,7 +107,7 @@ void answer(const asclinic_pkg::LeftRightInt32& msg) { ...@@ -107,7 +107,7 @@ void answer(const asclinic_pkg::LeftRightInt32& msg) {
float angular_velocity = dPhi / time_float; float angular_velocity = dPhi / time_float;
// Log current position and angular velocity // Log current position and angular velocity
ROS_INFO_STREAM("Current Position - X:" << x << ", Y:" << y << ", Phi:" << phi << ", Angular Velocity:" << angular_velocity); ROS_INFO_STREAM("Current Position - X:" << x << ", Y:" << y << ", Phi:" << phi << ", Angular Velocity:" << angular_velocity << ", Total distance:"<< S);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment