Skip to content

Commit

Permalink
RoboClaw: declutter, make it compile again
Browse files Browse the repository at this point in the history
  • Loading branch information
MaEtUgR committed Nov 13, 2023
1 parent f3ae28c commit db950df
Show file tree
Hide file tree
Showing 10 changed files with 40 additions and 366 deletions.
2 changes: 1 addition & 1 deletion boards/px4/fmu-v5x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_ROBOCLAW=y
CONFIG_DRIVERS_GPIO_MCP23009=y
Expand Down
2 changes: 1 addition & 1 deletion msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -226,8 +226,8 @@ set(msg_files
VehicleTrajectoryBezier.msg
VehicleTrajectoryWaypoint.msg
VtolVehicleStatus.msg
Wind.msg
WheelEncoders.msg
Wind.msg
YawEstimatorStatus.msg
)
list(SORT msg_files)
Expand Down
1 change: 0 additions & 1 deletion msg/WheelEncoders.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,3 @@ uint64 timestamp # time since system start (microseconds)

float32[4] wheel_angle #Wheel angle of encoder, if two wheels wheel_angle[0] = right wheel and wheel_angle[1] = left wheel. Else [0][1] = right and [2][3] are left.
float32[4] wheel_speed #Wheel speed of encoder, if two wheels wheel_angle[0] = right wheel and wheel_angle[1] = left wheel. Else [0][1] = right and [2][3] are left.

9 changes: 1 addition & 8 deletions src/drivers/roboclaw/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
# Copyright (c) 2015-2023 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
Expand Down Expand Up @@ -31,18 +31,11 @@
#
############################################################################

set(PARAM_PREFIX ROBOCLAW)

if(CONFIG_BOARD_IO)
set(PARAM_PREFIX ROBOCLAW)
endif()

px4_add_module(
MODULE drivers__roboclaw
MAIN roboclaw
COMPILE_FLAGS
SRCS
roboclaw_main.cpp
RoboClaw.cpp
MODULE_CONFIG
module.yaml
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/roboclaw/Kconfig
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
menuconfig DRIVERS_ROBOCLAW
bool "crsf_rc"
bool "roboclaw"
default n
---help---
Enable support for roboclaw
34 changes: 28 additions & 6 deletions src/drivers/roboclaw/RoboClaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,9 +78,7 @@
using namespace time_literals;

RoboClaw::RoboClaw(const char *deviceName, const char *baudRateParam) :
// ModuleParams(nullptr),
OutputModuleInterface(MODULE_NAME, px4::wq_configurations::hp_default)
// ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default)
{
strncpy(_storedDeviceName, deviceName, sizeof(_storedDeviceName) - 1);
_storedDeviceName[sizeof(_storedDeviceName) - 1] = '\0'; // Ensure null-termination
Expand Down Expand Up @@ -251,9 +249,9 @@ void RoboClaw::Run()

// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s pupdate;
_parameter_update_sub.copy(&pupdate);
// Read from topic to clear updated flag
parameter_update_s parameter_update;
_parameter_update_sub.copy(&parameter_update);

updateParams();
}
Expand Down Expand Up @@ -530,11 +528,35 @@ RoboClaw::RoboClawError RoboClaw::writeCommandWithPayload(e_command cmd, uint8_t

int RoboClaw::custom_command(int argc, char *argv[])
{
return 0;
return print_usage("unknown command");
}

int RoboClaw::print_usage(const char *reason)
{
if (reason) {
PX4_WARN("%s\n", reason);
}

PRINT_MODULE_DESCRIPTION(R"DESCR_STR(
### Description
This driver communicates over UART with the [Roboclaw motor driver](https://www.basicmicro.com/motor-controller).
It performs two tasks:
- Control the motors based on the OutputModuleInterface.
- Read the wheel encoders and publish the raw data in the `wheel_encoders` uORB topic
In order to use this driver, the Roboclaw should be put into Packet Serial mode (see the linked documentation), and
your flight controller's UART port should be connected to the Roboclaw as shown in the documentation.
The driver needs to be enabled using the parameter `RBCLW_SER_CFG`, the baudrate needs to be set correctly and
the address `RBCLW_ADDRESS` needs to match the ESC configuration.
The command to start this driver is: `$ roboclaw start <UART device> <baud rate>`
)DESCR_STR");

PRINT_MODULE_USAGE_NAME("roboclaw", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
return 0;
}

Expand Down
35 changes: 7 additions & 28 deletions src/drivers/roboclaw/RoboClaw.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,41 +36,23 @@
*
* RoboClaw Motor Driver
*
* references:
* http://downloads.orionrobotics.com/downloads/datasheets/motor_controller_robo_claw_R0401.pdf
*
* Product page: https://www.basicmicro.com/motor-controller
* Manual: https://downloads.basicmicro.com/docs/roboclaw_user_manual.pdf
*/

#pragma once

#include <poll.h>
#include <stdio.h>
#include <termios.h>
#include <lib/parameters/param.h>
#include <drivers/device/i2c.h>
#include <lib/mixer_module/mixer_module.hpp>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <sys/select.h>
#include <sys/time.h>
#include <pthread.h>
#include <unistd.h>

#include <uORB/Subscription.hpp>

#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/wheel_encoders.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>

#include <uORB/topics/differential_drive_control.h>

#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>

#include <lib/mixer_module/mixer_module.hpp>

#include <uORB/Publication.hpp>
#include <uORB/topics/wheel_encoders.h>

/**
* This is a driver for the RoboClaw motor controller
Expand Down Expand Up @@ -216,11 +198,8 @@ class RoboClaw : public ModuleBase<RoboClaw>, public OutputModuleInterface
struct timeval _uart_fd_timeout;

uORB::SubscriptionData<actuator_armed_s> _actuator_armed_sub{ORB_ID(actuator_armed)};
uORB::Subscription _differential_drive_control_sub{ORB_ID(differential_drive_control)};
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};

differential_drive_control_s _diff_drive_control{};

matrix::Vector2f _motor_control{0.0f, 0.0f};

uORB::Publication<wheel_encoders_s> _wheel_encoders_pub {ORB_ID(wheel_encoders)};
Expand Down
66 changes: 0 additions & 66 deletions src/drivers/roboclaw/RoboclawSerialDevice.hpp

This file was deleted.

Loading

0 comments on commit db950df

Please sign in to comment.