Skip to content

Commit

Permalink
Minor updates to README and bringup source file
Browse files Browse the repository at this point in the history
  • Loading branch information
TheNoobInventor committed Aug 24, 2024
1 parent 104cdc1 commit ac28493
Show file tree
Hide file tree
Showing 3 changed files with 59 additions and 65 deletions.
7 changes: 2 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ The following components were used in this project:
|15| 3 x 18650 batteries to power Motor Driver HAT|
|16| Female to Female Dupont jumper cables|
|17| Spare wires|
|18| Logitech C270 webcam|
|18| Logitech C270 webcam (optional)|

Some other tools or parts used in the project are as follows:

Expand Down Expand Up @@ -909,15 +909,14 @@ In rviz, set the initial pose using the `2D Pose Estimate` button in the toolbar
<img src=docs/images/gazebo_navigation.gif width="800">
</p>

TODO: add gif of navigation in Gazebo Fortress

Note about the pixels not part of the map

The blue arrow shows unfiltered odometry, while green shows the filtered odometry.

### Lidarbot

TODO: Prop robot and show different odometry movements in rviz. Then show the robot response when on the 'ground'

```
ros2 launch lidarbot_bringup lidarbot_bringup_launch.py
```
Expand All @@ -937,8 +936,6 @@ map_subscribe_transient_local:=true

Using navigation goal button from nav2 plugin

Use waypoint mode here

## Acknowledgment

- [Articulated Robotics](https://articulatedrobotics.xyz/)
Expand Down
115 changes: 56 additions & 59 deletions lidarbot_base/src/motor_encoder.c
Original file line number Diff line number Diff line change
Expand Up @@ -11,75 +11,72 @@ int left_wheel_direction = 1;
int right_wheel_direction = 1;

// Read wheel encoder values
void read_encoder_values(int *left_encoder_value, int *right_encoder_value)
{
*left_encoder_value = left_wheel_pulse_count;
*right_encoder_value = right_wheel_pulse_count;
void read_encoder_values(int *left_encoder_value, int *right_encoder_value) {
*left_encoder_value = left_wheel_pulse_count;
*right_encoder_value = right_wheel_pulse_count;
}

// Left wheel callback function
void left_wheel_pulse()
{
// left wheel direction
// 1 - forward
// 0 - backward

// Read encoder direction value for left wheel
left_wheel_direction = digitalRead(LEFT_WHL_ENC_DIR);

if(left_wheel_direction == 1)
left_wheel_pulse_count++;
else
left_wheel_pulse_count--;
void left_wheel_pulse() {
// left wheel direction
// 1 - forward
// 0 - backward

// Read encoder direction value for left wheel
left_wheel_direction = digitalRead(LEFT_WHL_ENC_DIR);

if (left_wheel_direction == 1)
left_wheel_pulse_count++;
else
left_wheel_pulse_count--;
}

// Right wheel callback function
void right_wheel_pulse()
{
// right wheel direction
// 1 - forward,
// 0 - backward

// Read encoder direction value for right wheel
right_wheel_direction = digitalRead(RIGHT_WHL_ENC_DIR);

if(right_wheel_direction = 1)
right_wheel_pulse_count++;
else
right_wheel_pulse_count--;
void right_wheel_pulse() {
// right wheel direction
// 1 - forward,
// 0 - backward

// Read encoder direction value for right wheel
right_wheel_direction = digitalRead(RIGHT_WHL_ENC_DIR);

if (right_wheel_direction == 1)
right_wheel_pulse_count++;
else
right_wheel_pulse_count--;
}

// Set each motor speed from the respective velocity command interface
void set_motor_speeds(double left_wheel_command, double right_wheel_command)
{
// Initialize DIR enum variables
DIR left_motor_direction;
DIR right_motor_direction;

// Tune motor speeds by adjusting the command coefficients. These are dependent on the number of encoder ticks. 3000 ticks and above work well with coefficients of 1.0
double left_motor_speed = ceil(left_wheel_command * 1.65);
double right_motor_speed = ceil(right_wheel_command * 1.65);

// Set motor directions
if(left_motor_speed > 0)
left_motor_direction = FORWARD;
else
left_motor_direction = BACKWARD;

if(right_motor_speed > 0)
right_motor_direction = FORWARD;
else
right_motor_direction = BACKWARD;

// Run motors with specified direction and speeds
Motor_Run(MOTORA, left_motor_direction, (int) abs(left_motor_speed));
Motor_Run(MOTORB, right_motor_direction, (int) abs(right_motor_speed));
void set_motor_speeds(double left_wheel_command, double right_wheel_command) {
// Initialize DIR enum variables
DIR left_motor_direction;
DIR right_motor_direction;

// Tune motor speeds by adjusting the command coefficients. These are
// dependent on the number of encoder ticks. 3000 ticks and above work well
// with coefficients of 1.0
double left_motor_speed = ceil(left_wheel_command * 1.65);
double right_motor_speed = ceil(right_wheel_command * 1.65);

// Set motor directions
if (left_motor_speed > 0)
left_motor_direction = FORWARD;
else
left_motor_direction = BACKWARD;

if (right_motor_speed > 0)
right_motor_direction = FORWARD;
else
right_motor_direction = BACKWARD;

// Run motors with specified direction and speeds
Motor_Run(MOTORA, left_motor_direction, (int)abs(left_motor_speed));
Motor_Run(MOTORB, right_motor_direction, (int)abs(right_motor_speed));
}

void handler(int signo)
{
Motor_Stop(MOTORA);
Motor_Stop(MOTORB);
void handler(int signo) {
Motor_Stop(MOTORA);
Motor_Stop(MOTORB);

exit(0);
exit(0);
}
2 changes: 1 addition & 1 deletion lidarbot_bringup/config/controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ imu_broadcaster:
sensor_name: mpu6050
frame_id: imu_link

# 500 data points used to calculated covariances
# 500 data points used to calculated covariances
static_covariance_orientation: [2.63882e-06, 0.0, 0.0, 0.0, 7.50018e-06, 0.0, 0.0, 0.0, 2.89257e-09]
static_covariance_angular_velocity: [2.71413e-07, 0.0, 0.0, 0.0, 6.79488e-07, 0.0, 0.0, 0.0, 4.37879e-07]
static_covariance_linear_acceleration: [0.00133755, 0.0, 0.0, 0.0, 0.000209753, 0.0, 0.0, 0.0, 0.00143276]

0 comments on commit ac28493

Please sign in to comment.