First flake environment
This commit is contained in:
@ -1,4 +1,4 @@
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
cmake_minimum_required(VERSION 3.24)
|
||||
project(mg_control)
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
@ -13,7 +13,6 @@ find_package(hardware_interface REQUIRED)
|
||||
find_package(rclcpp_lifecycle REQUIRED)
|
||||
find_package(rclcpp_components REQUIRED)
|
||||
include(FindPkgConfig)
|
||||
pkg_search_module(LIBSERIAL REQUIRED libserial)
|
||||
|
||||
add_library(
|
||||
mg_control
|
||||
@ -24,13 +23,11 @@ add_library(
|
||||
target_include_directories(
|
||||
mg_control
|
||||
PRIVATE
|
||||
${LIBSERIAL_INCLUDE_DIRS}
|
||||
include
|
||||
)
|
||||
|
||||
target_link_libraries(
|
||||
mg_control
|
||||
${LIBSERIAL_LIBRARIES}
|
||||
)
|
||||
|
||||
ament_target_dependencies(
|
||||
|
||||
@ -55,7 +55,7 @@
|
||||
</joint>
|
||||
|
||||
|
||||
<ros2_control name="mg-base" type="system">
|
||||
<ros2_control name="mg_base" type="system">
|
||||
<hardware>
|
||||
<plugin>mg_control/MgStepperInterface</plugin>
|
||||
</hardware>
|
||||
|
||||
@ -55,7 +55,7 @@
|
||||
</joint>
|
||||
|
||||
|
||||
<ros2_control name="mg-base" type="system">
|
||||
<ros2_control name="mg_base" type="system">
|
||||
<hardware>
|
||||
<plugin>mock_components/GenericSystem</plugin>
|
||||
<param name="calculate_dynamics">true</param>
|
||||
|
||||
@ -3,7 +3,7 @@
|
||||
#include <vector>
|
||||
#include <string>
|
||||
|
||||
#include "libserial/SerialPort.h"
|
||||
//#include "libserial/SerialPort.h"
|
||||
#include "hardware_interface/handle.hpp"
|
||||
#include "hardware_interface/system_interface.hpp"
|
||||
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
|
||||
@ -26,7 +26,7 @@ namespace mg {
|
||||
|
||||
private:
|
||||
std::string serial_port_name;
|
||||
LibSerial::SerialPort odrive_serial_interface;
|
||||
// LibSerial::SerialPort odrive_serial_interface;
|
||||
|
||||
double left_wheel_vel_cmd = 0;
|
||||
double left_wheel_pos_state = 0;
|
||||
|
||||
19
mg_control/package.nix
Normal file
19
mg_control/package.nix
Normal file
@ -0,0 +1,19 @@
|
||||
# Automatically generated by: ros2nix --distro jazzy
|
||||
{ lib, buildRosPackage, ament-cmake, ament-lint-auto, ament-lint-common, controller-manager, diff-drive-controller, hardware-interface, joint-state-broadcaster, libserial-dev, pluginlib, rclcpp, rclcpp-components, rclcpp-lifecycle, robot-state-publisher, ros2-control, ros2launch }:
|
||||
buildRosPackage rec {
|
||||
pname = "ros-jazzy-mg-control";
|
||||
version = "0.0.1";
|
||||
|
||||
src = ./.;
|
||||
|
||||
buildType = "ament_cmake";
|
||||
buildInputs = [ ament-cmake ];
|
||||
checkInputs = [ ament-lint-auto ament-lint-common ];
|
||||
propagatedBuildInputs = [ controller-manager diff-drive-controller hardware-interface joint-state-broadcaster libserial-dev pluginlib rclcpp rclcpp-components rclcpp-lifecycle robot-state-publisher ros2-control ros2launch ];
|
||||
nativeBuildInputs = [ ament-cmake ];
|
||||
|
||||
meta = {
|
||||
description = "Ros2 control compatible drivers for magrob";
|
||||
license = with lib.licenses; [ asl20 ];
|
||||
};
|
||||
}
|
||||
@ -8,11 +8,13 @@ CallbackReturn mg::MgStepperInterface::on_init(const hardware_interface::Hardwar
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
|
||||
/*
|
||||
if (info_.hardware_parameters.find("device_path") != info.hardware_parameters.end()) {
|
||||
serial_port_name = info_.hardware_parameters["device_path"];
|
||||
} else {
|
||||
serial_port_name = "/dev/ttyACM1";
|
||||
}
|
||||
*/
|
||||
|
||||
left_wheel_pos_state = 0;
|
||||
right_wheel_pos_state = 0;
|
||||
@ -22,6 +24,7 @@ CallbackReturn mg::MgStepperInterface::on_init(const hardware_interface::Hardwar
|
||||
}
|
||||
|
||||
CallbackReturn mg::MgStepperInterface::on_configure(const rclcpp_lifecycle::State&) {
|
||||
/*
|
||||
try {
|
||||
if (!odrive_serial_interface.IsOpen()) {
|
||||
odrive_serial_interface.Open(serial_port_name);
|
||||
@ -31,13 +34,16 @@ CallbackReturn mg::MgStepperInterface::on_configure(const rclcpp_lifecycle::Stat
|
||||
"Failed to open serial port (Is the stepper driver plugged in)");
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
*/
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
CallbackReturn mg::MgStepperInterface::on_shutdown(const rclcpp_lifecycle::State&) {
|
||||
/*
|
||||
if (odrive_serial_interface.IsOpen()) {
|
||||
odrive_serial_interface.Close();
|
||||
}
|
||||
*/
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
@ -66,6 +72,7 @@ hardware_interface::return_type mg::MgStepperInterface::read(const rclcpp::Time&
|
||||
}
|
||||
|
||||
hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time&, const rclcpp::Duration&) {
|
||||
/*
|
||||
union {
|
||||
std::array<u_char, sizeof(double)> bytes;
|
||||
double data;
|
||||
@ -79,5 +86,6 @@ hardware_interface::return_type mg::MgStepperInterface::write(const rclcpp::Time
|
||||
for (const auto& bt : value.bytes) { odrive_serial_interface.WriteByte(bt); }
|
||||
|
||||
} catch (const std::runtime_error& e) { return hardware_interface::return_type::ERROR; }
|
||||
*/
|
||||
return hardware_interface::return_type::OK;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user