Skip to content

Commit

Permalink
removed eronous divions by loop rate
Browse files Browse the repository at this point in the history
  • Loading branch information
VincidaB committed Apr 26, 2024
1 parent ea09e32 commit 06a7759
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
8 changes: 4 additions & 4 deletions omnidrive_rppico/hardware/omnibot_pico_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,10 +249,10 @@ hardware_interface::return_type omnidrive_rppico ::OmniDriveRpPicoHardware::writ
return hardware_interface::return_type::ERROR;
}

int motor_f_counts_per_loop = wheel_f_.cmd / wheel_f_.rads_per_count / cfg_.loop_rate;
int motor_l_counts_per_loop = wheel_l_.cmd / wheel_l_.rads_per_count / cfg_.loop_rate;
int motor_b_counts_per_loop = wheel_b_.cmd / wheel_b_.rads_per_count / cfg_.loop_rate;
int motor_r_counts_per_loop = wheel_r_.cmd / wheel_r_.rads_per_count / cfg_.loop_rate;
int motor_f_counts_per_loop = wheel_f_.cmd / wheel_f_.rads_per_count;
int motor_l_counts_per_loop = wheel_l_.cmd / wheel_l_.rads_per_count;
int motor_b_counts_per_loop = wheel_b_.cmd / wheel_b_.rads_per_count;
int motor_r_counts_per_loop = wheel_r_.cmd / wheel_r_.rads_per_count;



Expand Down
2 changes: 1 addition & 1 deletion src/ezbot_robot/config/omnidirectional_controller.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ omnidirectional_controller:
robot_radius: 0.15
wheel_radius: 0.03

publish_rate: 50.0
publish_rate: 30.0
odom_frame_id: odom
base_frame_id: base_link
pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
Expand Down

0 comments on commit 06a7759

Please sign in to comment.