-
Notifications
You must be signed in to change notification settings - Fork 5
Motor control
For this project we are using a DCX16S GB KL 12V DC motor, ENX16 EASY Absolute SSI encoder, and GPX16 A 21:1 gearbox, all of them made by Maxon motor.
We are using a FingerTech Robotics TinyESC v2.4 (specifications), a bi-directional brushed motor controller that can take battery voltage from 6.5 to 36 volts, and output a continuous current of 1.5A (3.0A peak). It includes undervoltage, overcurrent backwards polarity, and a BEC (battery eliminator circuit) protection.
The tinyESC is equipped with a 2-pin calibration connector, a 3-pin JST connector for your SIG, 5V, and GND lines to access a receiver, two bare lead wires for M1 and M2 to connect to your motor, and another set of two bare lead wires for Batt and GND to connect to a battery.
The motor that makes the Hokuyo LIDAR spin around its axis is controlled by a Teensy 3.2 board, with a 72MHz ARM Cortex M4 microcontroller.
In order to program the Teensy, you need to download the Arduino IDE, and the Teensyduino add-on.
Then, you'll need to add your Linux user to the dialout group, by running the following command:
sudo usermod -a -G dialout $USER
Next, copy the udev rules of the Teensy, so that you can always have read/write permissions on the serial port it gets assigned when you plug it in:
cd $DD2465_WS/src/spinning_lidar/spinning_lidar_motor_control/
sudo cp 49-teensy-udev.rules /etc/udev/rules.d/
NOTE: Before proceeding make sure that you have followed the procedure described in the Installation section.
Before uploading the code into the Teensy you'll need to build locally the rosserial_arduino dependencies. This is because we have some custom ROS messages and services for manipulating the motor remotely.
Run the following commands to build the required dependencies:
cd ~/Arduino/libraries/
rm -r ros_lib/
rosrun rosserial_arduino make_libraries.py .
If everything went well, you should be able to scroll up, and see the following message printed:
Exporting spinning_lidar_motor_control
Messages:
MotorState,
Services:
TurnMotorOnOff,ChangeTargetVelocity,
The Arduino files are located in spinning_lidar_motor_control/teensy_motor_control/
.
The main file is teensy_motor_control.ino, and it has two headers:
- motor_control.h: this is where all the code related to motor control is stored (PINs setup, encoders and PID)
- ros_comm.h: this is where all the ROS-related code is stored (node handler, publishers and services).
To send command to the motor and read its state, this node has to be running. To launch it, run:
roslaunch spinning_lidar_launch motor_control.launch
From the Teensy we publish a topic /spinning_lidar/motor_state
that contains the current angle and velocity of the sensor, the desired speed, and if the motor is stopped or not.
header:
seq: 107
stamp:
secs: 1512996391
nsecs: 184720022
frame_id: "/laser_axis"
stopped: True
curr_angle: 0.0
offset_angle: 0.0
curr_vel: 0.0
des_vel: 2.35619449615
The service /spinning_lidar/turn_motor_onoff
can be called to start/stop the motor.
Example:
rosservice call /spinning_lidar/turn_motor_onoff "stopped: false"
The service /spinning_lidar/change_motor_vel
can be called to start/stop the motor and change the desired velocity.
Example:
rosservice call /spinning_lidar/change_motor_vel "stopped: false
rot_vel: 3.00"