Skip to content

Commit

Permalink
Merge pull request #2 from srmainwaring/develop
Browse files Browse the repository at this point in the history
Release v0.2.0

- Simplify custom messages for servo data and commands
- Simplify parameters for base controller for in arduino controller
- Simplify the topic name for radio control data.
- Add a regression stage to the encoder filter
- Add Arduino firmware for servo controller and radio control decoder
- Add odometry and a tf broadcaster
- Add tuning parameters for odometry
  • Loading branch information
srmainwaring authored Jan 28, 2020
2 parents ef09cc3 + e97ad91 commit b069443
Show file tree
Hide file tree
Showing 49 changed files with 4,797 additions and 1,229 deletions.
314 changes: 252 additions & 62 deletions README.md

Large diffs are not rendered by default.

5 changes: 4 additions & 1 deletion ackermann_drive_controller/package.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,13 @@
<?xml version="1.0"?>
<package format="2">
<name>ackermann_drive_controller</name>
<version>0.0.0</version>
<version>0.2.0</version>
<description>Ackermann drive controller for a 6 wheel drive 4 wheel steering robot</description>
<maintainer email="[email protected]">Rhys Mainwaring</maintainer>
<license>BSD-3-Clause</license>
<url type="website">https://github.com/srmainwaring/curio</url>
<url type="repository">https://github.com/srmainwaring/curio</url>
<url type="bugtracker">https://github.com/srmainwaring/curio/issues</url>
<author email="[email protected]">Rhys Mainwaring</author>
<buildtool_depend>catkin</buildtool_depend>

Expand Down
75 changes: 61 additions & 14 deletions curio_base/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,18 @@ add_compile_options(-std=c++11)
# Find dependent catkin packages

find_package(catkin REQUIRED COMPONENTS
rospy
# serial
curio_description
curio_control
curio_msgs
geometry_msgs
joint_state_publisher
nav_msgs
robot_state_publisher
roscpp
rospy
serial
std_msgs
tf
)

################################################################################
Expand All @@ -23,31 +31,70 @@ catkin_python_setup()
# Declare catkin configuration

catkin_package(
# INCLUDE_DIRS include
LIBRARIES
INCLUDE_DIRS
include
LIBRARIES
curio_base
CATKIN_DEPENDS
rospy
# serial
curio_description
curio_control
curio_msgs
geometry_msgs
joint_state_publisher
nav_msgs
robot_state_publisher
roscpp
rospy
serial
std_msgs
tf
)

################################################################################
# Build

# include_directories(
# include
# ${catkin_INCLUDE_DIRS}
# )
include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_library(curio_base
src/lx16a_driver.cpp
)
target_link_libraries(curio_base ${catkin_LIBRARIES})

add_executable(lx16a_position_publisher
src/examples/lx16a_position_publisher.cpp
)
target_link_libraries(lx16a_position_publisher curio_base ${catkin_LIBRARIES})

################################################################################
# Install

install(TARGETS
curio_base
lx16a_position_publisher
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})

install(DIRECTORY include/curio_base/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})

catkin_install_python(PROGRAMS
nodes/curio_motor_controller
nodes/curio_base_controller
scripts/lx16a_cmd_vel_random.py
scripts/lx16a_cmd_vel_sinusoid.py
scripts/lx16a_cmd_vel_stepped.py
scripts/lx16a_driver_test.py
scripts/lx16a_encoder_calibration.py
scripts/lx16a_make_training_data.py
scripts/lx16a_odometry.py
scripts/lx16a_encoder_filter_test.py
scripts/lx16a_encoder_logger.py
scripts/lx16a_mean_filter_test.py
scripts/lx16a_odometry_test.py
scripts/lx16a_train_classifier.py
scripts/lx16a_train_regressor.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY config data launch
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
93 changes: 93 additions & 0 deletions curio_base/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
# LX-16A Learn

ML estimator to predict whether the position data from a LX-16A servo is in its valid range or not.

## Instructions

### Generate basic data

Run `roscore`:

```bash
roscore
```

Run rotary encoder node

```bash
roslaunch curio_base rotary_encoder.launch
```

Run the servo logger node:

```bash
rosrun curio_base lx16a_encoder_logger.py
```

Start `rqt` and use the topic publisher to the linear velocity component of `/cmd_vel`.

### Generate data from a simulation

#### Record a sample of `/cmd_vel`

Run `roscore`

```bash
roscore
```

Run the Gazebo simulation node:

```bash
roslaunch curio_gazebo curio_mars_world.launch
```

Run the `teleop_rc` node:

```bash
roslaunch curio_teleop teleop_rc.launch port:=/dev/cu.usbmodemFD5121
```

Relay `/cmd_vel` to `/ackermann_drive_controller/cmd_vel` for the controller:

```bash
rosrun topic_tools relay /cmd_vel /ackermann_drive_controller/cmd_vel
```

Start recording with `rosbag`:

```bash
rosbag record -o curio_mars cmd_vel
```

Drive the rover about the simulation using the RC unit.

#### Play a sample of `/cmd_vel`

Run `roscore`:

```bash
roscore
```

Run the rotary encoder node:

```bash
roslaunch curio_base rotary_encoder.launch
```

Run the servo logger node:

```bash
rosrun curio_base lx16a_encoder_logger.py
```

Play the `rosbag` using simulation time:

```bash
rosparam set use_sim_time true
rosplay --clock curio_mars_2020-01-11-16-49-30.bag
```

The calibration node will record the encoder count associated with the servo position
for the commanded duty.
61 changes: 61 additions & 0 deletions curio_base/config/base_controller.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
# Curio base controller parameters
#
# ROS frame convention for mobile robots:
#
# x
# ^
# | longatudinal dir
# |
# lateral dir y <-------
#
#
# Wheel geometry / servo location. The numbers are servo serial ids:
# two digits for wheel servos, three digits for steering servos.
#
# <- front wheel lat separation ->
# 11 / 111 |-----|-----| 21 / 212 ---
# | ^
# | front wheel lon separation
# <- mid wheel lat separation -> v
# 12 |-------|-------| 22 ---
# | ^
# | back wheel lon separation
# | v
# 13 / 131 |------|------| 23 / 233 ---
# <- back wheel lat separation ->
#

# Servo driver port settings
# port: /dev/cu.wchusbserialfd5110
port: /dev/ttyACM0
baudrate: 115200
timeout: 1.0

# Update frequencies: control loop
control_frequency: 20.0

# Robot dimensions and limits
max_linear_velocity: 0.37 # [m/s]
max_angular_velocity: 1.45 # [rad/s]

wheel_radius: 0.060
mid_wheel_lat_separation: 0.52
front_wheel_lat_separation: 0.47
front_wheel_lon_separation: 0.28
back_wheel_lat_separation: 0.47
back_wheel_lon_separation: 0.25

# Odometry calibration / tuning (default 1.0 - no adjustment)
wheel_radius_multiplier: 1.0
mid_wheel_lat_separation_multiplier: 0.96875

# Wheel servo parameters
wheel_servo_ids: [ 11, 12, 13, 21, 22, 23]
wheel_servo_lon_labels: ['front', 'mid', 'back', 'front', 'mid', 'back']
wheel_servo_lat_labels: [ 'left', 'left', 'left', 'right', 'right', 'right']

# Steering servo parameters
steer_servo_ids: [ 111, 131, 211, 231]
steer_servo_lon_labels: ['front', 'back', 'front', 'back']
steer_servo_lat_labels: [ 'left', 'left', 'right', 'right']
steer_servo_angle_offsets: [ -10, -5, 40, 20]
110 changes: 0 additions & 110 deletions curio_base/config/motor_controller.yaml

This file was deleted.

Binary file added curio_base/data/lx16a_dataset.zip
Binary file not shown.
Binary file added curio_base/data/lx16a_labelled_data.zip
Binary file not shown.
Binary file added curio_base/data/lx16a_tree_classifier.joblib
Binary file not shown.
Binary file added curio_base/data/lx16a_tree_regressor.joblib
Binary file not shown.
Loading

0 comments on commit b069443

Please sign in to comment.