Skip to content

Commit

Permalink
perseus_hardware: Initial MCB+VESC implementation done
Browse files Browse the repository at this point in the history
  • Loading branch information
RandomSpaceship committed Dec 21, 2024
1 parent 36eae43 commit 355cedf
Show file tree
Hide file tree
Showing 6 changed files with 515 additions and 97 deletions.
3 changes: 1 addition & 2 deletions software/ros_ws/src/perseus_hardware/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,7 @@ target_include_directories(
${PROJECT_NAME}
PRIVATE $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/priv_include>)

target_link_libraries(${PROJECT_NAME} PUBLIC hi_can)
target_link_libraries(${PROJECT_NAME} PRIVATE hi_can_raw)
target_link_libraries(${PROJECT_NAME} PUBLIC hi_can_raw)
ament_target_dependencies(${PROJECT_NAME} PUBLIC
${THIS_PACKAGE_INCLUDE_DEPENDS})

Expand Down
20 changes: 20 additions & 0 deletions software/ros_ws/src/perseus_hardware/include/mcb_system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include <hardware_interface/hardware_info.hpp>
#include <hardware_interface/system_interface.hpp>
#include <hardware_interface/types/hardware_interface_return_values.hpp>
#include <hi_can_raw.hpp>
#include <optional>
#include <rclcpp/clock.hpp>
#include <rclcpp/duration.hpp>
#include <rclcpp/logger.hpp>
Expand All @@ -19,15 +21,33 @@ namespace perseus_hardware
{
public:
RCLCPP_SHARED_PTR_DEFINITIONS(McbSystemHardware)
virtual ~McbSystemHardware();

hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override;

private:
// note: using std::optional so we can delay initialisation until on_configure
std::optional<hi_can::RawCanInterface> _canInterface;
std::optional<hi_can::PacketManager> _packetManager;

/// @brief The last time we tried to transmit and had an error
/// @details Used to throttle transmissions (and error messages) so we don't build up a massive transmit queue when the bus comes online again
rclcpp::Time _lastTransmitError;

std::vector<hi_can::parameters::legacy::drive::motors::EscParameterGroup> _parameterGroups;
std::vector<unsigned long> _escIds;
std::vector<double> _commandSpeeds;
std::vector<double> _realSpeeds;
std::vector<double> _realPositions;
std::vector<double> _realCurrents;
std::vector<double> _realTemperatures;
};
}
22 changes: 14 additions & 8 deletions software/ros_ws/src/perseus_hardware/include/vesc_system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <hardware_interface/hardware_info.hpp>
#include <hardware_interface/system_interface.hpp>
#include <hardware_interface/types/hardware_interface_return_values.hpp>
#include <hi_can.hpp>
#include <hi_can_raw.hpp>
#include <optional>
#include <rclcpp/clock.hpp>
#include <rclcpp/duration.hpp>
Expand All @@ -21,27 +21,33 @@ namespace perseus_hardware
{
public:
RCLCPP_SHARED_PTR_DEFINITIONS(VescSystemHardware)
virtual ~VescSystemHardware();

hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::return_type read(const rclcpp::Time& time, const rclcpp::Duration& period) override;
hardware_interface::return_type write(const rclcpp::Time& time, const rclcpp::Duration& period) override;

auto& get_logger() const { return *_logger; }
auto get_clock() const { return _clock; }
auto& get_info() const { return info_; }

private:
// note: using std::optional so we can delay initialisation until on_configure
std::optional<hi_can::RawCanInterface> _canInterface;
std::optional<hi_can::PacketManager> _packetManager;

/// @brief The last time we tried to transmit and had an error
/// @details Used to throttle transmissions (and error messages) so we don't build up a massive transmit queue when the bus comes online again
rclcpp::Time _lastTransmitError;

std::vector<hi_can::parameters::drive::vesc::VescParameterGroup> _parameterGroups;
std::vector<unsigned long> _vescIds;
std::vector<double> _commandSpeeds;
std::vector<double> _realSpeeds;
std::vector<double> _realPositions;

std::shared_ptr<rclcpp::Logger> _logger;
rclcpp::Clock::SharedPtr _clock;
std::vector<double> _realCurrents;
std::vector<double> _realTemperatures;
};
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#include <rclcpp/logger.hpp>
#include <rclcpp/macros.hpp>

#define CHECK_INTERFACE_COUNT(_logger, _joint, _interface_type, _interface_name, _count) \
#define CHECK_EQ_INTERFACE_COUNT(_logger, _joint, _interface_type, _interface_name, _count) \
do \
{ \
if ((_joint)._interface_type.size() != (_count)) \
Expand All @@ -16,6 +16,18 @@
return hardware_interface::CallbackReturn::ERROR; \
} \
} while (0)
#define CHECK_GE_INTERFACE_COUNT(_logger, _joint, _interface_type, _interface_name, _count) \
do \
{ \
if ((_joint)._interface_type.size() >= (_count)) \
{ \
RCLCPP_FATAL((_logger), "Joint '%s' has %zu " _interface_name " interfaces found, expected at least %d", \
(_joint).name.c_str(), \
(_joint)._interface_type.size(), \
_count); \
return hardware_interface::CallbackReturn::ERROR; \
} \
} while (0)

#define CHECK_INTERFACE_NAME(_logger, _joint, _interface_type, _interface_name, _interface_index, _expected_name) \
do \
Expand Down
Loading

0 comments on commit 355cedf

Please sign in to comment.