Skip to content

Commit

Permalink
rover interface:use vehicle thrust and torque setpoint instead of act…
Browse files Browse the repository at this point in the history
…uator controls
  • Loading branch information
haitomatic committed Oct 4, 2023
1 parent 9fab676 commit c3464bb
Show file tree
Hide file tree
Showing 2 changed files with 41 additions and 17 deletions.
42 changes: 30 additions & 12 deletions src/drivers/rover_interface/RoverInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ void RoverInterface::Run()
ActionRequestUpdate();

// Check for actuator controls command to rover
if (!_kill_switch && _armed) { ActuatorControlsUpdate(); }
if (!_kill_switch && _armed) { VehicleTorqueAndThrustUpdate(); }

// Check for vehicle control mode
VehicleControlModeUpdate();
Expand All @@ -219,18 +219,35 @@ void RoverInterface::Run()
}


void RoverInterface::ActuatorControlsUpdate()
void RoverInterface::VehicleTorqueAndThrustUpdate()
{
if (_actuator_controls_sub.updated()) {
actuator_controls_s actuator_controls_msg;

if (_actuator_controls_sub.copy(&actuator_controls_msg)) {
auto throttle = (_is_manual_mode ? _manual_throttle_max : _mission_throttle_max) *
actuator_controls_msg.control[actuator_controls_s::INDEX_THROTTLE];
auto steering = actuator_controls_msg.control[actuator_controls_s::INDEX_YAW];
_scout->SetMotionCommand(throttle, steering);
bool do_update = false;

// Check torque setppoint update
if (_vehicle_torque_setpoint_sub.updated()) {
vehicle_torque_setpoint_s vehicle_torque_setpoint_msg;

if (_vehicle_torque_setpoint_sub.copy(&vehicle_torque_setpoint_msg)) {
_yaw_control = vehicle_torque_setpoint_msg.xyz[2];
do_update = true;
}
}

// Check thrust setpoint update
if (_vehicle_thrust_setpoint_sub.updated()) {
vehicle_thrust_setpoint_s vehicle_thrust_setpoint_msg;

if (_vehicle_thrust_setpoint_sub.copy(&vehicle_thrust_setpoint_msg)) {
_throttle_control = vehicle_thrust_setpoint_msg.xyz[0];
do_update = true;
}
}

if (do_update) {
auto throttle = (_is_manual_mode ? _manual_throttle_max : _mission_throttle_max) * _throttle_control;
auto steering = _yaw_control;
_scout->SetMotionCommand(throttle, steering);
}
}


Expand Down Expand Up @@ -340,8 +357,9 @@ void RoverInterface::print_status()
PX4_INFO("Rover is armed: %s. Kill switch: %s", _armed ? "true" : "false", _kill_switch ? "true" : "false");

// Subscription info
PX4_INFO("Subscribed to topics: %s, %s",
_actuator_controls_sub.get_topic()->o_name,
PX4_INFO("Subscribed to topics: %s, %s, %s",
_vehicle_thrust_setpoint_sub.get_topic()->o_name,
_vehicle_torque_setpoint_sub.get_topic()->o_name,
_actuator_armed_sub.get_topic()->o_name);

// Publication info
Expand Down
16 changes: 11 additions & 5 deletions src/drivers/rover_interface/RoverInterface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,8 @@
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/Publication.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_thrust_setpoint.h>
#include <uORB/topics/vehicle_torque_setpoint.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/action_request.h>
#include <uORB/topics/rover_status.h>
Expand All @@ -33,7 +34,7 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem

static constexpr uint64_t SystemVersionQueryLimitMs{10_ms};

static constexpr uint64_t ActuatorControlSubIntervalMs{50_ms};
static constexpr uint64_t ControlSubIntervalMs{50_ms};

public:
static const char *const CAN_IFACE;
Expand All @@ -51,7 +52,7 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem
void Init();
void Run() override;

void ActuatorControlsUpdate();
void VehicleTorqueAndThrustUpdate();
void ActuatorArmedUpdate();
void ActionRequestUpdate();
void VehicleControlModeUpdate();
Expand Down Expand Up @@ -82,15 +83,20 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem

float _mission_throttle_max;

float _throttle_control;

float _yaw_control;

scoutsdk::ProtocolVersion _protocol_version{scoutsdk::ProtocolVersion::AGX_V2};

const char *_can_iface{nullptr};

scoutsdk::ScoutRobot *_scout{nullptr};

// Subscription
uORB::SubscriptionInterval _actuator_controls_sub{ORB_ID(actuator_controls_0), ActuatorControlSubIntervalMs};
uORB::SubscriptionInterval _actuator_armed_sub{ORB_ID(actuator_armed)};
uORB::SubscriptionInterval _vehicle_thrust_setpoint_sub{ORB_ID(vehicle_thrust_setpoint), ControlSubIntervalMs};
uORB::SubscriptionInterval _vehicle_torque_setpoint_sub{ORB_ID(vehicle_torque_setpoint), ControlSubIntervalMs};
uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)};
uORB::Subscription _action_request_sub{ORB_ID(action_request)};
uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)};

Expand Down

0 comments on commit c3464bb

Please sign in to comment.