Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rover: add wheel encoder support #6588

Merged
merged 5 commits into from
Jul 13, 2017
Merged

Conversation

rmackay9
Copy link
Contributor

@rmackay9 rmackay9 commented Jul 13, 2017

This PR adds initial support for Rovers to read from up to two "quadrature" wheel encoders (the most common type of wheel encoder apparently).

Details on the signals produced by a quadrature encoder can be found on the Wikipedia Rotary encoder page (look for "Incremental rotary encoder").

This PR adds:

  • new AP_WheelEncoder library for reading signals from two wheel encoders. Reading from the sensor has been tested on these motors from Pololu.com on my eLAB VEK rover. The "A" and "B" wires from each motor were attached to AUX3 ~ AUX6 of a Cube (aka Pixhawk2).
  • library includes new parameters for configuring the wheel encoders including defining the pins to be used, scaling and wheel position (which will be required for the EKF integration).
  • 10hz dataflash logging message ("WENC") which records the total distance for each wheel and signal quality at 10hz

This PR was tested by driving down my block and checking the dataflash logs:
drivetest

Some items to address in future PRs:

  • integrate the wheel encoder output with the EKF. This should allow velocity and position estimates without a GPS or stereo camera.
  • use the wheel encoder within a new low level speed controller perhaps within the AP_MotorsUGV library to provide better control of the vehicle (it will be better because errors in the wheel speed can be caught before they propagate to higher level estimates such as vehicle speed, heading or position)
  • the signal quality should be changed to cover a shorter period of time - currently it measures the total quality as the percentage of good signals since startup.
  • add new mavlink message to report wheel encoder sensor data to ground station in real time.

AP_Param::setup_object_defaults(this, var_info);

// init state and drivers
memset(state,0,sizeof(state));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nicpic : miss space after comma

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

fixed in follow up commit.

if (state[instance].total_count == 0) {
return 0.0f;
}
return constrain_float((1.0f - ((float)state[instance].error_count / (float)state[instance].total_count)) * 100.0f, 0.0f, 100.0f);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we should reset total_count and error_count with the first one that overflow !

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

thanks for the review. I'm going to leave this unresolved because I think even with my little rover (which thus has a very high number of events coming back from the wheel encoder), it would need to travel about 200km before an overflow occurred. Also more importantly, I'm pretty sure we will need to change this signal quality to shorten the period of time it covers. I suspect that work will resolve the potential overflow. Thanks again for the review.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yep I didn't make the calculation ... 200km is fine, your motor died before !
About the period, yes we can probably improve the time windows with some better statistic, but it is a futur enhancement

@patrickpoirier51
Copy link

patrickpoirier51 commented Jul 13, 2017

Looking at the ROS model, they have implemented a low level PID for the ifferential_drive, it could be quite interesting to expose a similar structure so ArduPilot could offer a direct compatibility to ROS:
from: http://wiki.ros.org/differential_drive
image

Please note that ROS just added a new diff_drive package http://wiki.ros.org/diff_drive_controller that is addind the skid steering.
There is a discussion here about implementation of the skid steer: ros-controls/ros_controllers#100

@OXINARF OXINARF added the Rover label Jul 13, 2017
@rmackay9
Copy link
Contributor Author

@patrickpoirier51, thanks for that. I definitely agree we should add a low level velocity controller using the wheel encoder(s) probably both for the main throttle and skid-steering rovers. That plus getting the wheel encoder stuff into the EKF will be a big jump forward for Rover.

@rmackay9 rmackay9 merged commit d61731c into ArduPilot:master Jul 13, 2017
@priseborough
Copy link
Contributor

We can either:

  1. Convert these measurements to an equivalent delta position measurement insides the driver and provide an accessor compatible with the existing or modified EKF odometry interface that uses delta position measurements in the body fame taken at a specified sensor location which in this instance will be at the wheel contact patch.

or

  1. Create a new interface in the EKF that accepts total distance travelled. That will require the EKF to monitor the change in distance for each wheel separately requiring it to know the wheel ID. I am not initially in favour of this approach.

@priseborough
Copy link
Contributor

I should also add that there is theoretically no difference in performance with these two approaches, just where the conversion from cumulative to delta position occurs.

// return true if the instance is enabled
bool enabled(uint8_t instance) const;

// get the position of the wheel associated with the wheel encoder
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we add some information on the axis system this is defined in and the units.

@rmackay9 rmackay9 deleted the wheel-enc branch November 23, 2017 05:19
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

5 participants