Skip to content

Commit

Permalink
Remove from asserts
Browse files Browse the repository at this point in the history
  • Loading branch information
tabiosg committed Oct 7, 2023
1 parent 936cbe0 commit 78e4360
Show file tree
Hide file tree
Showing 7 changed files with 35 additions and 23 deletions.
18 changes: 12 additions & 6 deletions src/esw/can_library/can_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,16 +24,22 @@ concept TriviallyCopyable = std::is_trivially_copyable_v<T>;

class CANManager {
public:
CANManager(ros::NodeHandle& n, const std::string& name) {
m_can_publisher = n.advertise<mrover::CAN>("can_requests", 1);
CANManager(ros::NodeHandle& nh, const std::string& name) {
m_can_publisher = nh.advertise<mrover::CAN>("can_requests", 1);
std::string can_bus_name = "can/" + name + "/bus";
assert(n.getParam(can_bus_name, m_bus));
assert(nh.hasParam(can_bus_name));
int bus;
nh.getParam(can_bus_name, bus);
m_bus = static_cast<int>(bus);
std::string can_id_name = "can/" + name + "/id";
assert(n.getParam(can_id_name, m_id));
assert(nh.hasParam(can_id_name));
int id;
nh.getParam(can_id_name, id);
m_id = static_cast<int>(id);

assert(n.hasParam("can/messages"));
XmlRpc::XmlRpcValue can_messages;
n.getParam("can/messages", can_messages);
assert(nh.hasParam("can/messages"));
nh.getParam("can/messages", can_messages);
assert(can_messages.getType() == XmlRpc::XmlRpcValue::TypeStruct);
for (auto [messageName, messageId]: can_messages) {
if (messageId.getType() == XmlRpc::XmlRpcValue::TypeInt) {
Expand Down
15 changes: 10 additions & 5 deletions src/esw/drive_bridge/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ int main(int argc, char** argv) {

// Load motor multipliers from the ROS parameter server
XmlRpc::XmlRpcValue driveControllers;
assert(nh.getParam("drive/controllers", driveControllers));
assert(nh.hasParam("drive/controllers"));
nh.getParam("drive/controllers", driveControllers);
assert(driveControllers.getType() == XmlRpc::XmlRpcValue::TypeStruct);
for (const auto& driveName: driveNames) {
assert(driveControllers.hasMember(driveName));
Expand All @@ -46,20 +47,24 @@ int main(int argc, char** argv) {
// Load rover dimensions and other parameters from the ROS parameter server
float roverWidth = 0.0f;
float roverLength = 0.0f;
assert(nh.getParam("rover/width", roverWidth));
assert(nh.getParam("rover/length", roverLength));
assert(nh.hasParam("rover/width"));
nh.getParam("rover/width", roverWidth);
assert(nh.hasParam("rover/length"));
nh.getParam("rover/length", roverLength);
WHEEL_DISTANCE_INNER = roverWidth / 2.0f;
WHEEL_DISTANCE_OUTER = std::sqrt(((roverWidth / 2.0f) * (roverWidth / 2.0f)) + ((roverLength / 2.0f) * (roverLength / 2.0f)));

float ratioMotorToWheel = 0.0f;
assert(nh.getParam("wheel/gear_ratio", ratioMotorToWheel));
assert(nh.hasParam("wheel/gear_ratio"));
nh.getParam("wheel/gear_ratio", ratioMotorToWheel);
// To convert m/s to rev/s, multiply by this constant. Divide by circumference, multiply by gear ratio.
float wheelRadius = 0.0f;
nh.getParam("wheel/radius", wheelRadius);
WHEELS_M_S_TO_MOTOR_REV_S = (1.0f / (wheelRadius * 2.0f * static_cast<float>(std::numbers::pi))) * ratioMotorToWheel;

float maxSpeedMPerS = 0.0f;
assert(nh.getParam("rover/max_speed", maxSpeedMPerS));
assert(nh.hasParam("rover/max_speed"));
nh.getParam("rover/max_speed", maxSpeedMPerS);
assert(maxSpeedMPerS > 0.0f);

MAX_MOTOR_SPEED_REV_S = maxSpeedMPerS * WHEELS_M_S_TO_MOTOR_REV_S;
Expand Down
2 changes: 1 addition & 1 deletion src/esw/motor_library/brushed.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ class BrushedController : public Controller {
void set_desired_velocity(float velocity) override;
void set_desired_position(float position) override;

BrushedController(ros::NodeHandle& n, const std::string& name) : Controller(n, name) {}
BrushedController(ros::NodeHandle& nh, const std::string& name) : Controller(nh, name) {}
~BrushedController() override = default;

private:
Expand Down
2 changes: 1 addition & 1 deletion src/esw/motor_library/brushless.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class BrushlessController : public Controller {
void set_desired_velocity(float velocity) override; // in rev/s
void set_desired_position(float position) override;

BrushlessController(ros::NodeHandle& n, const std::string& name) : Controller(n, name) {
BrushlessController(ros::NodeHandle& nh, const std::string& name) : Controller(nh, name) {
torque = 0.3f;
}
~BrushlessController() override = default;
Expand Down
2 changes: 1 addition & 1 deletion src/esw/motor_library/controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@

class Controller {
public:
Controller(ros::NodeHandle& n, const std::string& name) : name{name}, can_manager{CANManager{n, name}} {}
Controller(ros::NodeHandle& nh, const std::string& name) : name{name}, can_manager{CANManager{nh, name}} {}

virtual ~Controller() = default;

Expand Down
17 changes: 9 additions & 8 deletions src/esw/motor_library/motors_manager.cpp
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
#include "motors_manager.hpp"

MotorsManager::MotorsManager(ros::NodeHandle& n, const std::string& groupName, const std::vector<std::string>& controllerNames) {
MotorsManager::MotorsManager(ros::NodeHandle& nh, const std::string& groupName, const std::vector<std::string>& controllerNames) {
motorGroupName = groupName;
motorNames = controllerNames;
// Load motor controllers configuration from the ROS parameter server
XmlRpc::XmlRpcValue controllersRoot;
assert(n.getParam("motors/controllers", controllersRoot));
assert(nh.hasParam("motors/controllers"));
nh.getParam("motors/controllers", controllersRoot);
assert(controllersRoot.getType() == XmlRpc::XmlRpcValue::TypeStruct);
for (const std::string& name: controllerNames) {
assert(controllersRoot[name].hasMember("type") &&
Expand All @@ -14,10 +15,10 @@ MotorsManager::MotorsManager(ros::NodeHandle& n, const std::string& groupName, c
assert(type == "brushed" || type == "brushless");

if (type == "brushed") {
auto temp = std::make_unique<BrushedController>(n, name);
auto temp = std::make_unique<BrushedController>(nh, name);
controllers[name] = std::move(temp);
} else if (type == "brushless") {
auto temp = std::make_unique<BrushlessController>(n, name);
auto temp = std::make_unique<BrushlessController>(nh, name);
controllers[name] = std::move(temp);
}

Expand All @@ -27,12 +28,12 @@ MotorsManager::MotorsManager(ros::NodeHandle& n, const std::string& groupName, c
updateLastConnection();

// Subscribe to the ROS topic for commands
ros::Subscriber moveThrottleSub = n.subscribe<mrover::Throttle>(groupName + "_throttle_cmd", 1, &MotorsManager::moveMotorsThrottle, this);
ros::Subscriber moveVelocitySub = n.subscribe<mrover::Velocity>(groupName + "_velocity_cmd", 1, &MotorsManager::moveMotorsVelocity, this);
ros::Subscriber movePositionSub = n.subscribe<mrover::Position>(groupName + "_position_cmd", 1, &MotorsManager::moveMotorsPosition, this);
ros::Subscriber moveThrottleSub = nh.subscribe<mrover::Throttle>(groupName + "_throttle_cmd", 1, &MotorsManager::moveMotorsThrottle, this);
ros::Subscriber moveVelocitySub = nh.subscribe<mrover::Velocity>(groupName + "_velocity_cmd", 1, &MotorsManager::moveMotorsVelocity, this);
ros::Subscriber movePositionSub = nh.subscribe<mrover::Position>(groupName + "_position_cmd", 1, &MotorsManager::moveMotorsPosition, this);

// Create a 0.1 second heartbeat timer
ros::Timer heartbeatTimer = n.createTimer(ros::Duration(0.1), &MotorsManager::heartbeatCallback, this);
ros::Timer heartbeatTimer = nh.createTimer(ros::Duration(0.1), &MotorsManager::heartbeatCallback, this);
}

Controller& MotorsManager::get_controller(std::string const& name) {
Expand Down
2 changes: 1 addition & 1 deletion src/esw/motor_library/motors_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class MotorsManager {
public:
MotorsManager() = default;

MotorsManager(ros::NodeHandle& n, const std::string& groupName, const std::vector<std::string>& controllerNames);
MotorsManager(ros::NodeHandle& nh, const std::string& groupName, const std::vector<std::string>& controllerNames);

Controller& get_controller(std::string const& name);

Expand Down

0 comments on commit 78e4360

Please sign in to comment.