mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 11:06:04 +08:00
delete unused md25 driver
This commit is contained in:
@@ -34,7 +34,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
#lights/rgbled_ncp5623c
|
#lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -34,7 +34,6 @@ px4_add_board(
|
|||||||
#lights/rgbled_ncp5623c
|
#lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -35,7 +35,6 @@ px4_add_board(
|
|||||||
#lights/rgbled_ncp5623c
|
#lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -39,7 +39,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -40,7 +40,6 @@ px4_add_board(
|
|||||||
#lights/rgbled
|
#lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
#mkblctrl
|
#mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -32,7 +32,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -37,7 +37,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -35,7 +35,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -43,7 +43,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -43,7 +43,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -41,7 +41,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -35,7 +35,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -35,7 +35,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -36,7 +36,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
#optical_flow # all available optical flow drivers
|
#optical_flow # all available optical flow drivers
|
||||||
optical_flow/px4flow
|
optical_flow/px4flow
|
||||||
|
|||||||
@@ -36,7 +36,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
#lights/rgbled_pwm
|
#lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -39,7 +39,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
pca9685
|
pca9685
|
||||||
|
|||||||
@@ -38,7 +38,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -39,7 +39,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
pca9685
|
pca9685
|
||||||
|
|||||||
@@ -31,7 +31,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
pca9685
|
pca9685
|
||||||
|
|||||||
@@ -38,7 +38,6 @@ px4_add_board(
|
|||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -39,7 +39,6 @@ px4_add_board(
|
|||||||
#lights/rgbled_ncp5623c
|
#lights/rgbled_ncp5623c
|
||||||
lights/rgbled_pwm
|
lights/rgbled_pwm
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
#mkblctrl
|
#mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#pca9685
|
#pca9685
|
||||||
|
|||||||
@@ -39,7 +39,6 @@ px4_add_board(
|
|||||||
lights/rgbled
|
lights/rgbled
|
||||||
lights/rgbled_ncp5623c
|
lights/rgbled_ncp5623c
|
||||||
magnetometer # all available magnetometer drivers
|
magnetometer # all available magnetometer drivers
|
||||||
#md25
|
|
||||||
mkblctrl
|
mkblctrl
|
||||||
optical_flow # all available optical flow drivers
|
optical_flow # all available optical flow drivers
|
||||||
#osd
|
#osd
|
||||||
|
|||||||
@@ -1,42 +0,0 @@
|
|||||||
############################################################################
|
|
||||||
#
|
|
||||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
|
||||||
#
|
|
||||||
# Redistribution and use in source and binary forms, with or without
|
|
||||||
# modification, are permitted provided that the following conditions
|
|
||||||
# are met:
|
|
||||||
#
|
|
||||||
# 1. Redistributions of source code must retain the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer.
|
|
||||||
# 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer in
|
|
||||||
# the documentation and/or other materials provided with the
|
|
||||||
# distribution.
|
|
||||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
# used to endorse or promote products derived from this software
|
|
||||||
# without specific prior written permission.
|
|
||||||
#
|
|
||||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
# POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
#
|
|
||||||
############################################################################
|
|
||||||
px4_add_module(
|
|
||||||
MODULE drivers__md25
|
|
||||||
MAIN md25
|
|
||||||
COMPILE_FLAGS
|
|
||||||
SRCS
|
|
||||||
md25.cpp
|
|
||||||
md25_main.cpp
|
|
||||||
DEPENDS
|
|
||||||
)
|
|
||||||
|
|
||||||
File diff suppressed because it is too large
Load Diff
@@ -1,309 +0,0 @@
|
|||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file md25.cpp
|
|
||||||
*
|
|
||||||
* Driver for MD25 I2C Motor Driver
|
|
||||||
*
|
|
||||||
* references:
|
|
||||||
* http://www.robot-electronics.co.uk/htm/md25tech.htm
|
|
||||||
* http://www.robot-electronics.co.uk/files/rpi_md25.c
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <poll.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <uORB/Subscription.hpp>
|
|
||||||
#include <uORB/topics/actuator_controls.h>
|
|
||||||
#include <drivers/device/i2c.h>
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This is a driver for the MD25 motor controller utilizing the I2C interface.
|
|
||||||
*/
|
|
||||||
class MD25 : public device::I2C
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
|
|
||||||
/**
|
|
||||||
* modes
|
|
||||||
*
|
|
||||||
* NOTE: this driver assumes we are always
|
|
||||||
* in mode 0!
|
|
||||||
*
|
|
||||||
* seprate speed mode:
|
|
||||||
* motor speed1 = speed1
|
|
||||||
* motor speed2 = speed2
|
|
||||||
* turn speed mode:
|
|
||||||
* motor speed1 = speed1 + speed2
|
|
||||||
* motor speed2 = speed2 - speed2
|
|
||||||
* unsigned:
|
|
||||||
* full rev (0), stop(128), full fwd (255)
|
|
||||||
* signed:
|
|
||||||
* full rev (-127), stop(0), full fwd (128)
|
|
||||||
*
|
|
||||||
* modes numbers:
|
|
||||||
* 0 : unsigned separate (default)
|
|
||||||
* 1 : signed separate
|
|
||||||
* 2 : unsigned turn
|
|
||||||
* 3 : signed turn
|
|
||||||
*/
|
|
||||||
enum e_mode {
|
|
||||||
MODE_UNSIGNED_SPEED = 0,
|
|
||||||
MODE_SIGNED_SPEED,
|
|
||||||
MODE_UNSIGNED_SPEED_TURN,
|
|
||||||
MODE_SIGNED_SPEED_TURN,
|
|
||||||
};
|
|
||||||
|
|
||||||
/** commands */
|
|
||||||
enum e_cmd {
|
|
||||||
CMD_RESET_ENCODERS = 32,
|
|
||||||
CMD_DISABLE_SPEED_REGULATION = 48,
|
|
||||||
CMD_ENABLE_SPEED_REGULATION = 49,
|
|
||||||
CMD_DISABLE_TIMEOUT = 50,
|
|
||||||
CMD_ENABLE_TIMEOUT = 51,
|
|
||||||
CMD_CHANGE_I2C_SEQ_0 = 160,
|
|
||||||
CMD_CHANGE_I2C_SEQ_1 = 170,
|
|
||||||
CMD_CHANGE_I2C_SEQ_2 = 165,
|
|
||||||
};
|
|
||||||
|
|
||||||
/** control channels */
|
|
||||||
enum e_channels {
|
|
||||||
CH_SPEED_LEFT = 0,
|
|
||||||
CH_SPEED_RIGHT
|
|
||||||
};
|
|
||||||
|
|
||||||
/**
|
|
||||||
* constructor
|
|
||||||
* @param deviceName the name of the device e.g. "/dev/md25"
|
|
||||||
* @param bus the I2C bus
|
|
||||||
* @param address the adddress on the I2C bus
|
|
||||||
* @param speed the speed of the I2C communication
|
|
||||||
*/
|
|
||||||
MD25(const char *deviceName,
|
|
||||||
int bus,
|
|
||||||
uint16_t address,
|
|
||||||
uint32_t speed = 100000);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* deconstructor
|
|
||||||
*/
|
|
||||||
virtual ~MD25() = default;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return software version
|
|
||||||
*/
|
|
||||||
uint8_t getVersion();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return speed of motor, normalized (-1, 1)
|
|
||||||
*/
|
|
||||||
float getMotor1Speed();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return speed of motor 2, normalized (-1, 1)
|
|
||||||
*/
|
|
||||||
float getMotor2Speed();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return number of rotations since reset
|
|
||||||
*/
|
|
||||||
float getRevolutions1();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return number of rotations since reset
|
|
||||||
*/
|
|
||||||
float getRevolutions2();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return battery voltage, volts
|
|
||||||
*/
|
|
||||||
float getBatteryVolts();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return motor 1 current, amps
|
|
||||||
*/
|
|
||||||
float getMotor1Current();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return motor 2 current, amps
|
|
||||||
*/
|
|
||||||
float getMotor2Current();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return the motor acceleration
|
|
||||||
* controls motor speed change (1-10)
|
|
||||||
* accel rate | time for full fwd. to full rev.
|
|
||||||
* 1 | 6.375 s
|
|
||||||
* 2 | 1.6 s
|
|
||||||
* 3 | 0.675 s
|
|
||||||
* 5(default) | 1.275 s
|
|
||||||
* 10 | 0.65 s
|
|
||||||
*/
|
|
||||||
uint8_t getMotorAccel();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return motor output mode
|
|
||||||
* */
|
|
||||||
e_mode getMode();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @return current command register value
|
|
||||||
*/
|
|
||||||
e_cmd getCommand();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* resets the encoders
|
|
||||||
* @return non-zero -> error
|
|
||||||
* */
|
|
||||||
int resetEncoders();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* enable/disable speed regulation
|
|
||||||
* @return non-zero -> error
|
|
||||||
*/
|
|
||||||
int setSpeedRegulation(bool enable);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* set the timeout for the motors
|
|
||||||
* enable/disable timeout (motor stop)
|
|
||||||
* after 2 sec of no i2c messages
|
|
||||||
* @return non-zero -> error
|
|
||||||
*/
|
|
||||||
int setTimeout(bool enable);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* sets the device address
|
|
||||||
* can only be done with one MD25
|
|
||||||
* on the bus
|
|
||||||
* @return non-zero -> error
|
|
||||||
*/
|
|
||||||
int setDeviceAddress(uint8_t address);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* set motor acceleration
|
|
||||||
* @param accel
|
|
||||||
* controls motor speed change (1-10)
|
|
||||||
* accel rate | time for full fwd. to full rev.
|
|
||||||
* 1 | 6.375 s
|
|
||||||
* 2 | 1.6 s
|
|
||||||
* 3 | 0.675 s
|
|
||||||
* 5(default) | 1.275 s
|
|
||||||
* 10 | 0.65 s
|
|
||||||
*/
|
|
||||||
int setMotorAccel(uint8_t accel);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* set motor 1 speed
|
|
||||||
* @param normSpeed normalize speed between -1 and 1
|
|
||||||
* @return non-zero -> error
|
|
||||||
*/
|
|
||||||
int setMotor1Speed(float normSpeed);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* set motor 2 speed
|
|
||||||
* @param normSpeed normalize speed between -1 and 1
|
|
||||||
* @return non-zero -> error
|
|
||||||
*/
|
|
||||||
int setMotor2Speed(float normSpeed);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* main update loop that updates MD25 motor
|
|
||||||
* speeds based on actuator publication
|
|
||||||
*/
|
|
||||||
void update();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* probe for device
|
|
||||||
*/
|
|
||||||
virtual int probe();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* search for device
|
|
||||||
*/
|
|
||||||
int search();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* read data from i2c
|
|
||||||
*/
|
|
||||||
int readData();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* print status
|
|
||||||
*/
|
|
||||||
void status(char *string, size_t n);
|
|
||||||
|
|
||||||
private:
|
|
||||||
/** poll structure for control packets */
|
|
||||||
struct pollfd _controlPoll;
|
|
||||||
|
|
||||||
/** actuator controls subscription */
|
|
||||||
uORB::SubscriptionData<actuator_controls_s> _actuators;
|
|
||||||
|
|
||||||
// local copy of data from i2c device
|
|
||||||
uint8_t _version;
|
|
||||||
float _motor1Speed;
|
|
||||||
float _motor2Speed;
|
|
||||||
float _revolutions1;
|
|
||||||
float _revolutions2;
|
|
||||||
float _batteryVoltage;
|
|
||||||
float _motor1Current;
|
|
||||||
float _motor2Current;
|
|
||||||
uint8_t _motorAccel;
|
|
||||||
e_mode _mode;
|
|
||||||
e_cmd _command;
|
|
||||||
|
|
||||||
// private methods
|
|
||||||
int _writeUint8(uint8_t reg, uint8_t value);
|
|
||||||
int _writeInt8(uint8_t reg, int8_t value);
|
|
||||||
float _uint8ToNorm(uint8_t value);
|
|
||||||
uint8_t _normToUint8(float value);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* set motor control mode,
|
|
||||||
* this driver assumed we are always in mode 0
|
|
||||||
* so we don't let the user change the mode
|
|
||||||
* @return non-zero -> error
|
|
||||||
*/
|
|
||||||
int _setMode(e_mode);
|
|
||||||
};
|
|
||||||
|
|
||||||
// unit testing
|
|
||||||
int md25Test(const char *deviceName, uint8_t bus, uint8_t address);
|
|
||||||
|
|
||||||
// sine testing
|
|
||||||
int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency);
|
|
||||||
|
|
||||||
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
|
|
||||||
@@ -1,311 +0,0 @@
|
|||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @ file md25.cpp
|
|
||||||
*
|
|
||||||
* Driver for MD25 I2C Motor Driver
|
|
||||||
*
|
|
||||||
* references:
|
|
||||||
* http://www.robot-electronics.co.uk/htm/md25tech.htm
|
|
||||||
* http://www.robot-electronics.co.uk/files/rpi_md25.c
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <px4_platform_common/px4_config.h>
|
|
||||||
#include <px4_platform_common/log.h>
|
|
||||||
#include <unistd.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <stdlib.h>
|
|
||||||
#include <string.h>
|
|
||||||
#include <math.h>
|
|
||||||
|
|
||||||
#include <parameters/param.h>
|
|
||||||
|
|
||||||
#include <arch/board/board.h>
|
|
||||||
#include "md25.hpp"
|
|
||||||
|
|
||||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
|
||||||
static bool thread_running = false; /**< Deamon status flag */
|
|
||||||
static int deamon_task; /**< Handle of deamon task / thread */
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Deamon management function.
|
|
||||||
*/
|
|
||||||
extern "C" __EXPORT int md25_main(int argc, char *argv[]);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Mainloop of deamon.
|
|
||||||
*/
|
|
||||||
int md25_thread_main(int argc, char *argv[]);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Print the correct usage.
|
|
||||||
*/
|
|
||||||
static void usage(const char *reason);
|
|
||||||
|
|
||||||
static void
|
|
||||||
usage(const char *reason)
|
|
||||||
{
|
|
||||||
if (reason) {
|
|
||||||
PX4_WARN("%s", reason);
|
|
||||||
}
|
|
||||||
|
|
||||||
PX4_INFO("usage: md25 {start|stop|read|status|search|test|change_address}");
|
|
||||||
exit(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* The deamon app only briefly exists to start
|
|
||||||
* the background job. The stack size assigned in the
|
|
||||||
* Makefile does only apply to this management task.
|
|
||||||
*
|
|
||||||
* The actual stack size should be set in the call
|
|
||||||
* to task_create().
|
|
||||||
*/
|
|
||||||
int md25_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
|
|
||||||
if (argc < 2) {
|
|
||||||
usage("missing command");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "start")) {
|
|
||||||
|
|
||||||
if (thread_running) {
|
|
||||||
printf("md25 already running\n");
|
|
||||||
/* this is not an error */
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
thread_should_exit = false;
|
|
||||||
deamon_task = px4_task_spawn_cmd("md25",
|
|
||||||
SCHED_DEFAULT,
|
|
||||||
SCHED_PRIORITY_MAX - 10,
|
|
||||||
2048,
|
|
||||||
md25_thread_main,
|
|
||||||
(const char **)argv);
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "test")) {
|
|
||||||
|
|
||||||
if (argc < 4) {
|
|
||||||
printf("usage: md25 test bus address\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[2], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t address = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
md25Test(deviceName, bus, address);
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "sine")) {
|
|
||||||
|
|
||||||
if (argc < 6) {
|
|
||||||
printf("usage: md25 sine bus address amp freq\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[2], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t address = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
float amplitude = atof(argv[4]);
|
|
||||||
|
|
||||||
float frequency = atof(argv[5]);
|
|
||||||
|
|
||||||
md25Sine(deviceName, bus, address, amplitude, frequency);
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "probe")) {
|
|
||||||
if (argc < 4) {
|
|
||||||
printf("usage: md25 probe bus address\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[2], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t address = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
MD25 md25(deviceName, bus, address);
|
|
||||||
|
|
||||||
int ret = md25.probe();
|
|
||||||
|
|
||||||
if (ret == OK) {
|
|
||||||
printf("MD25 found on bus %d at address 0x%X\n", bus, md25.get_device_address());
|
|
||||||
|
|
||||||
} else {
|
|
||||||
printf("MD25 not found on bus %d\n", bus);
|
|
||||||
}
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "read")) {
|
|
||||||
if (argc < 4) {
|
|
||||||
printf("usage: md25 read bus address\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[2], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t address = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
MD25 md25(deviceName, bus, address);
|
|
||||||
|
|
||||||
// print status
|
|
||||||
char buf[400];
|
|
||||||
md25.status(buf, sizeof(buf));
|
|
||||||
printf("%s\n", buf);
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "search")) {
|
|
||||||
if (argc < 3) {
|
|
||||||
printf("usage: md25 search bus\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[2], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t address = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
MD25 md25(deviceName, bus, address);
|
|
||||||
|
|
||||||
md25.search();
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "change_address")) {
|
|
||||||
if (argc < 5) {
|
|
||||||
printf("usage: md25 change_address bus old_address new_address\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[2], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t old_address = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t new_address = strtoul(argv[4], nullptr, 0);
|
|
||||||
|
|
||||||
MD25 md25(deviceName, bus, old_address);
|
|
||||||
|
|
||||||
int ret = md25.setDeviceAddress(new_address);
|
|
||||||
|
|
||||||
if (ret == OK) {
|
|
||||||
printf("MD25 new address set to 0x%X\n", new_address);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
printf("MD25 failed to set address to 0x%X\n", new_address);
|
|
||||||
}
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "stop")) {
|
|
||||||
thread_should_exit = true;
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "status")) {
|
|
||||||
if (thread_running) {
|
|
||||||
printf("\tmd25 app is running\n");
|
|
||||||
|
|
||||||
} else {
|
|
||||||
printf("\tmd25 app not started\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
usage("unrecognized command");
|
|
||||||
exit(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
int md25_thread_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
printf("[MD25] starting\n");
|
|
||||||
|
|
||||||
if (argc < 5) {
|
|
||||||
// extra md25 in arg list since this is a thread
|
|
||||||
printf("usage: md25 start bus address\n");
|
|
||||||
exit(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
const char *deviceName = "/dev/md25";
|
|
||||||
|
|
||||||
uint8_t bus = strtoul(argv[3], nullptr, 0);
|
|
||||||
|
|
||||||
uint8_t address = strtoul(argv[4], nullptr, 0);
|
|
||||||
|
|
||||||
// start
|
|
||||||
MD25 md25(deviceName, bus, address);
|
|
||||||
|
|
||||||
thread_running = true;
|
|
||||||
|
|
||||||
// loop
|
|
||||||
while (!thread_should_exit) {
|
|
||||||
md25.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
// exit
|
|
||||||
printf("[MD25] exiting.\n");
|
|
||||||
thread_running = false;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
|
|
||||||
Reference in New Issue
Block a user