Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ build/
install/
log/
.vscode/
.codex

# Byte-compiled / optimized / DLL files
__pycache__/
Expand Down
69 changes: 69 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
{
"files.associations": {
"cctype": "cpp",
"clocale": "cpp",
"cmath": "cpp",
"cstdarg": "cpp",
"cstddef": "cpp",
"cstdio": "cpp",
"cstdlib": "cpp",
"cstring": "cpp",
"ctime": "cpp",
"cwchar": "cpp",
"cwctype": "cpp",
"array": "cpp",
"atomic": "cpp",
"bit": "cpp",
"bitset": "cpp",
"chrono": "cpp",
"compare": "cpp",
"complex": "cpp",
"concepts": "cpp",
"condition_variable": "cpp",
"cstdint": "cpp",
"deque": "cpp",
"forward_list": "cpp",
"list": "cpp",
"map": "cpp",
"set": "cpp",
"string": "cpp",
"unordered_map": "cpp",
"unordered_set": "cpp",
"vector": "cpp",
"exception": "cpp",
"algorithm": "cpp",
"functional": "cpp",
"iterator": "cpp",
"memory": "cpp",
"memory_resource": "cpp",
"numeric": "cpp",
"optional": "cpp",
"random": "cpp",
"ratio": "cpp",
"string_view": "cpp",
"system_error": "cpp",
"tuple": "cpp",
"type_traits": "cpp",
"utility": "cpp",
"fstream": "cpp",
"initializer_list": "cpp",
"iomanip": "cpp",
"iosfwd": "cpp",
"iostream": "cpp",
"istream": "cpp",
"limits": "cpp",
"mutex": "cpp",
"new": "cpp",
"numbers": "cpp",
"ostream": "cpp",
"semaphore": "cpp",
"sstream": "cpp",
"stdexcept": "cpp",
"stop_token": "cpp",
"streambuf": "cpp",
"thread": "cpp",
"cinttypes": "cpp",
"typeindex": "cpp",
"typeinfo": "cpp"
}
}
49 changes: 49 additions & 0 deletions src/description/ros2_control/science/science.dc.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="dc_ros2_control" params="name">

<ros2_control name="${name}" type="system">

<hardware>
<plugin>dc_ros2_control/DCHardwareInterface</plugin>
<param name="update_rate">20</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">1</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_id">0x70</param>
</hardware>

<joint name="dc_auger">
<param name="node_id">0</param>
<param name="joint_type">revolute</param>

<param name="gear_ratio">50.9</param>
<param name="inverted">true</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
</joint>

<joint name="dc_scoop">
<param name="node_id">2</param>
<param name="joint_type">revolute</param>

<param name="gear_ratio">50.9</param>
<param name="inverted">true</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
</joint>

</ros2_control>

</xacro:macro>

</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -55,13 +55,13 @@
<state_interface name="velocity"/>
</joint>

<joint name="servo_scoop_a">
<joint name="scoop_a">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
</joint>

<joint name="servo_scoop_b">
<joint name="scoop_b">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
<plugin>servo_ros2_control/SERVOHardwareInterface</plugin>
<param name="update_rate">20</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">1</param> <!-- 0 for off, 1 for on -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_id">0x80</param>
</hardware>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,39 +7,37 @@

<hardware>
<plugin>stepper_ros2_control/STEPPERHardwareInterface</plugin>
<param name="update_rate">10</param> <!-- Hz -->
<param name="logger_rate">5</param> <!-- Hz -->
<param name="logger_state">0</param> <!-- 0 for off, 1 for on -->
<param name="can_interface">can0</param>
<param name="can_id">0x90</param>
</hardware>

<joint name="stepper_motor_a">
<param name="node_id">0x0</param>
<param name="gear_ratio">1</param>
<param name="rated_max">20</param>
<param name="joint_type">continuous</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<param name="initial_position">0.0</param>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<param name="gear_ratio">1</param>

<!-- TEMPORARY PARAMETERS -->
<param name="joint_orientation">1</param>

</joint>

<joint name="stepper_motor_b">
<param name="node_id">0x1</param>
<param name="gear_ratio">1</param>
<param name="rated_max">20</param>
<param name="joint_type">continuous</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
<param name="initial_position">0.0</param>
<state_interface name="velocity"/>
<state_interface name="motor_temperature"/>
<state_interface name="torque_current"/>
<param name="gear_ratio">1</param>

<!-- TEMPORARY PARAMETERS -->
<param name="joint_orientation">1</param>

</joint>

</ros2_control>

</xacro:macro>

</robot>
</robot>
8 changes: 6 additions & 2 deletions src/description/urdf/athena_science.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@

<xacro:include filename="$(find description)/ros2_control/science/science.mock.ros2_control.xacro"/>

<xacro:include filename="$(find description)/ros2_control/science/science.stepper.ros2_control.xacro" />
<xacro:include filename="$(find description)/ros2_control/science/science.servo.ros2_control.xacro" />
<xacro:include filename="$(find description)/ros2_control/science/science.stepper.ros2_control.xacro"/>
<xacro:include filename="$(find description)/ros2_control/science/science.servo.ros2_control.xacro"/>
<xacro:include filename="$(find description)/ros2_control/science/science.dc.ros2_control.xacro"/>
<xacro:include filename="$(find description)/ros2_control/science/science.talon.ros2_control.xacro"/>
<xacro:include filename="$(find description)/ros2_control/science/science.laser.ros2_control.xacro"/>

Expand All @@ -30,6 +31,9 @@
<!-- Import servo ros2_control description -->
<xacro:servo_ros2_control name="servo"/>

<!-- Import dc ros2_control description -->
<xacro:dc_ros2_control name="dc"/>

<!-- Import talon ros2_control description -->
<xacro:talon_ros2_control name="talon"/>

Expand Down
70 changes: 70 additions & 0 deletions src/hardware_interfaces/dc_ros2_control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
cmake_minimum_required(VERSION 3.8)
project(dc_ros2_control)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
hardware_interface
pluginlib
rclcpp
rclcpp_lifecycle
umdloop_can_library
)

find_package(ament_cmake REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

include_directories(include)

add_library(dc_ros2_control SHARED
src/dc_hardware_interface.cpp
)

target_compile_features(dc_ros2_control PUBLIC cxx_std_20)

target_include_directories(dc_ros2_control PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/dc_ros2_control>
)

# Link umdloop_can_library directly via CMake target (same as servo HWI)
target_link_libraries(dc_ros2_control PUBLIC umdloop_can_library::umdloop_can_library)

ament_target_dependencies(dc_ros2_control PUBLIC
hardware_interface
pluginlib
rclcpp
rclcpp_lifecycle
)

# Export hardware plugin
pluginlib_export_plugin_description_file(hardware_interface dc_hardware_interface.xml)

# Install
install(
DIRECTORY include/
DESTINATION include/dc_ros2_control
)

install(TARGETS dc_ros2_control
EXPORT export_dc_ros2_control
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_export_targets(export_dc_ros2_control)
ament_export_include_directories(include)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<library path="dc_ros2_control"> <!-- library path which corresponds to cmake. -->
<class name="dc_ros2_control/DCHardwareInterface"
type="dc_ros2_control::DCHardwareInterface"
base_class_type="hardware_interface::SystemInterface"> <!-- name and type rely on the namespace in the hardware interface. Keep this in mind -->
<description>
UMDLoop's ros2_control plugin for the DC motors
</description>
</class>
</library>
Loading