Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow custom configuration #243

Merged
merged 6 commits into from
May 15, 2024
Merged
Show file tree
Hide file tree
Changes from 4 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
10 changes: 8 additions & 2 deletions andino_description/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,14 @@ This package holds the urdf description of the robot.

<img src="docs/robot_rviz.png">

In the `urdf` folder you have the URDF files that contain the description of the robot, divided in different modules and merged into `andino.urdf.xacro` file.

## Configuration

In case you want to change the physical properties of some of the components of the robot, you can do it modifying the default YAML files inside the `config/andino` folder.

You can even add your own configuration files in another directory in the `config` folder, and passing this directory to the main file using `yaml_config_dir` xacro argument inside the launch files.
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved

## Launch Files

For launching robot state publisher for filling up static tf information and serving the description of the robot. Typically used during robot bringup.
Expand All @@ -16,5 +24,3 @@ For launching the robot state publisher and providing some visualization with rv
```
ros2 launch andino_description view_andino.launch.py
```


6 changes: 6 additions & 0 deletions andino_description/config/andino/hardware.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
left_wheel_name: left_wheel_joint
right_wheel_name: right_wheel_joint
serial_device: /dev/ttyUSB_ARDUINO
baud_rate: 57600
timeout: 1000
enc_ticks_per_rev: 585
11 changes: 6 additions & 5 deletions andino_description/launch/andino_description.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch import LaunchDescription, LaunchContext
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration
Expand All @@ -41,15 +41,16 @@

def generate_launch_description():

# Obtains andino_description's share directory path.
pkg_andino_description = get_package_share_directory('andino_description')
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved

# Arguments
rsp_argument = DeclareLaunchArgument('rsp', default_value='true',
description='Run robot state publisher node.')

# Obtains andino_description's share directory path.
pkg_andino_description = get_package_share_directory('andino_description')

# Obtain urdf from xacro files.
doc = xacro.process_file(os.path.join(pkg_andino_description, 'urdf', 'andino.urdf.xacro'))
arguments = {'yaml_config_dir': os.path.join(pkg_andino_description, 'config', 'andino')}
doc = xacro.process_file(os.path.join(pkg_andino_description, 'urdf', 'andino.urdf.xacro'), mappings = arguments)
robot_desc = doc.toprettyxml(indent=' ')
params = {'robot_description': robot_desc,
'publish_frequency': 30.0}
Expand Down
9 changes: 5 additions & 4 deletions andino_description/launch/view_andino.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,9 @@

def generate_launch_description():

# Obtains andino_description's share directory path.
pkg_andino_description = get_package_share_directory('andino_description')
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved

# Arguments
rviz_argument = DeclareLaunchArgument('rviz', default_value='true',
description='Open RViz.')
Expand All @@ -49,11 +52,9 @@ def generate_launch_description():
jsp_argument = DeclareLaunchArgument('jsp', default_value='true',
description='Run joint state publisher node.')

# Obtains andino_description's share directory path.
pkg_andino_description = get_package_share_directory('andino_description')

# Obtain urdf from xacro files.
doc = xacro.process_file(os.path.join(pkg_andino_description, 'urdf', 'andino.urdf.xacro'))
arguments = {'yaml_config_dir': os.path.join(pkg_andino_description, 'config', 'andino')}
doc = xacro.process_file(os.path.join(pkg_andino_description, 'urdf', 'andino.urdf.xacro'), mappings = arguments)
robot_desc = doc.toprettyxml(indent=' ')
params = {'robot_description': robot_desc,
'publish_frequency': 30.0}
Expand Down
5 changes: 5 additions & 0 deletions andino_description/urdf/andino.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@
<xacro:property name="sensor_yaml" value="$(arg yaml_config_dir)/sensors.yaml" />
<xacro:property name="sensor_prop" value="${xacro.load_yaml(sensor_yaml)}"/>

<xacro:property name="hardware_yaml" value="$(arg yaml_config_dir)/hardware.yaml" />
<xacro:property name="hardware_props" value="${xacro.load_yaml(hardware_yaml)}"/>


<!-- Footprint link -->
<xacro:footprint wheel_props="${wheel_props}" />

Expand Down Expand Up @@ -89,6 +93,7 @@
<!-- ros2_control -->
<xacro:if value="$(arg use_real_ros_control)">
<xacro:include filename="$(find ${package_name})/urdf/include/andino_control.urdf.xacro" />
<xacro:control hardware_props="${hardware_props}" />
</xacro:if>


Expand Down
67 changes: 38 additions & 29 deletions andino_description/urdf/include/andino_control.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,34 +1,43 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- TODO(francocipollone): This xacro should be part of andino_control package instead.-->
<ros2_control name="RealRobot" type="system">
<hardware>
<plugin>andino_base/DiffDriveAndino</plugin>
<!-- TODO(francocipollone): Parameters like loop_rate, device, baud_rate, etc should be loaded from a file or passed via the launch file as xacro args -->
<param name="left_wheel_name">left_wheel_joint</param>
<param name="right_wheel_name">right_wheel_joint</param>
<param name="serial_device">/dev/ttyUSB_ARDUINO</param>
<param name="baud_rate">57600</param>
<param name="timeout">1000</param>
<param name="enc_ticks_per_rev">585</param>
</hardware>
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-5</param>
<param name="max">5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-5</param>
<param name="max">5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>
<!-- ===================== Control xacro =========================================

params:
- hardware_props [dictionary]: hardware properties loaded from the YAML file.
-->

<xacro:macro name="control" params="hardware_props" >
jballoffet marked this conversation as resolved.
Show resolved Hide resolved

<!-- TODO(francocipollone): This xacro should be part of andino_control package instead.-->
<ros2_control name="RealRobot" type="system">
<hardware>
<plugin>andino_base/DiffDriveAndino</plugin>
<param name="left_wheel_name">${hardware_props['left_wheel_name']}</param>
<param name="right_wheel_name">${hardware_props['right_wheel_name']}</param>
<param name="serial_device">${hardware_props['serial_device']}</param>
<param name="baud_rate">${hardware_props['baud_rate']}</param>
<param name="timeout">1${hardware_props['timeout']}</param>
JesusSilvaUtrera marked this conversation as resolved.
Show resolved Hide resolved
<param name="enc_ticks_per_rev">${hardware_props['enc_ticks_per_rev']}</param>
</hardware>
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-5</param>
<param name="max">5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-5</param>
<param name="max">5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>

</xacro:macro>

</robot>
Loading