-
Notifications
You must be signed in to change notification settings - Fork 192
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Browse files
Browse the repository at this point in the history
* Create a demo that uses transmissions (#226) * add copy for transmission demo and set in the urdf * Renamed to rrbot_transmissions * Changed reduction value of transmission2 * Added the rrbot_transmissions_system_position_only Exact copy of rrbot_system_position_only for now. Using it from the transmission demo * Moved logger into its own variable * Uncrustify * Renamed hw interface to joint. Added actuator interfaces * Formatting. Remove comments * Using transmissions for joint and actuator interfaces Added a helper object to manage the joint to transmissions to actuator data handling * Propagating data between all the interfaces * Cleanup. Added some consts * Simulate motor motion * Added logging to periodically show interface data * Refactored the parameters a bit. Removed unused ones * Added try/catches where needed Checking joint consistency in the description not required. Already done by the parser * Added transmission demo to README * Use clang-format instead * rename transmissions ros2_control macro * Remove unnecessary actuator parameters * Typo * Removed gazebo, mock hardware and fake sensors from the transmission demo * Missing 'explicit' from constructor * Further cleanup of gazebo, mock hardware and fake sensors from the transmission demo * branding fix * Remove pointer definitions Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com> * Fixed comment about reserve Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com> * Renamed member variable and added description --------- Co-authored-by: Noel Jimenez <noel.jimenez@pal-robotics.com> Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com> (cherry picked from commit 1007b1d) * Fix preformatted block * fix header guard --------- Co-authored-by: Jordan Palacios <jordan.palacios@pal-robotics.com> Co-authored-by: Bence Magyar <bence.magyar.robotics@gmail.com>
- Loading branch information
1 parent
a8959bb
commit 0e71a38
Showing
11 changed files
with
657 additions
and
24 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
70 changes: 70 additions & 0 deletions
70
ros2_control_demo_bringup/launch/rrbot_transmissions_system_position_only.launch.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,70 @@ | ||
# Copyright 2021 Stogl Robotics Consulting UG (haftungsbeschränkt) | ||
# | ||
# Licensed under the Apache License, Version 2.0 (the "License"); | ||
# you may not use this file except in compliance with the License. | ||
# You may obtain a copy of the License at | ||
# | ||
# http://www.apache.org/licenses/LICENSE-2.0 | ||
# | ||
# Unless required by applicable law or agreed to in writing, software | ||
# distributed under the License is distributed on an "AS IS" BASIS, | ||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
# See the License for the specific language governing permissions and | ||
# limitations under the License. | ||
|
||
from launch import LaunchDescription | ||
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription | ||
from launch.launch_description_sources import PythonLaunchDescriptionSource | ||
from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir | ||
|
||
|
||
def generate_launch_description(): | ||
# Declare arguments | ||
declared_arguments = [] | ||
declared_arguments.append( | ||
DeclareLaunchArgument( | ||
"prefix", | ||
default_value='""', | ||
description="Prefix of the joint names, useful for \ | ||
multi-robot setup. If changed than also joint names in the controllers' configuration \ | ||
have to be updated.", | ||
) | ||
) | ||
declared_arguments.append( | ||
DeclareLaunchArgument( | ||
"slowdown", default_value="50.0", description="Slowdown factor of the RRbot." | ||
) | ||
) | ||
declared_arguments.append( | ||
DeclareLaunchArgument( | ||
"robot_controller", | ||
default_value="forward_position_controller", | ||
description="Robot controller to start.", | ||
) | ||
) | ||
declared_arguments.append( | ||
DeclareLaunchArgument( | ||
"start_rviz", | ||
default_value="true", | ||
description="Start RViz2 automatically with this launch file.", | ||
) | ||
) | ||
|
||
# Initialize Arguments | ||
prefix = LaunchConfiguration("prefix") | ||
slowdown = LaunchConfiguration("slowdown") | ||
robot_controller = LaunchConfiguration("robot_controller") | ||
start_rviz = LaunchConfiguration("start_rviz") | ||
|
||
base_launch = IncludeLaunchDescription( | ||
PythonLaunchDescriptionSource([ThisLaunchFileDir(), "/rrbot_base.launch.py"]), | ||
launch_arguments={ | ||
"description_file": "rrbot_transmissions_system_position_only.urdf.xacro", | ||
"prefix": prefix, | ||
"slowdown": slowdown, | ||
"robot_controller": robot_controller, | ||
"start_rviz": start_rviz, | ||
}.items(), | ||
) | ||
|
||
return LaunchDescription(declared_arguments + [base_launch]) |
50 changes: 50 additions & 0 deletions
50
...rbot_description/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,50 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | ||
|
||
<xacro:macro name="rrbot_transmissions_system_position_only" params="name prefix use_gazebo:=^|false use_fake_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0"> | ||
|
||
<ros2_control name="${name}" type="system"> | ||
|
||
<hardware> | ||
<plugin>ros2_control_demo_hardware/RRBotTransmissionsSystemPositionOnlyHardware</plugin> | ||
<param name="actuator_slowdown">${slowdown}</param> | ||
</hardware> | ||
|
||
<joint name="${prefix}joint1"> | ||
<command_interface name="position"> | ||
<param name="min">-1</param> | ||
<param name="max">1</param> | ||
</command_interface> | ||
<state_interface name="position"/> | ||
</joint> | ||
|
||
<joint name="${prefix}joint2"> | ||
<command_interface name="position"> | ||
<param name="min">-1</param> | ||
<param name="max">1</param> | ||
</command_interface> | ||
<state_interface name="position"/> | ||
</joint> | ||
|
||
<transmission name="transmission1"> | ||
<plugin>transmission_interface/SimpleTransmission</plugin> | ||
<actuator name="actuator1" role="actuator1"/> | ||
<joint name="joint1" role="joint1"> | ||
<mechanical_reduction>2.0</mechanical_reduction> | ||
<offset>0.0</offset> | ||
</joint> | ||
</transmission> | ||
|
||
<transmission name="transmission2"> | ||
<plugin>transmission_interface/SimpleTransmission</plugin> | ||
<actuator name="actuator2" role="actuator2"/> | ||
<joint name="joint2" role="joint2"> | ||
<mechanical_reduction>4.0</mechanical_reduction> | ||
<offset>0.0</offset> | ||
</joint> | ||
</transmission> | ||
</ros2_control> | ||
|
||
</xacro:macro> | ||
|
||
</robot> |
38 changes: 38 additions & 0 deletions
38
...mo_description/rrbot_description/urdf/rrbot_transmissions_system_position_only.urdf.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,38 @@ | ||
<?xml version="1.0"?> | ||
<!-- Revolute-Revolute Manipulator --> | ||
<!-- | ||
Copied and modified from ROS1 example - | ||
https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_description/urdf/rrbot.xacro | ||
--> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot"> | ||
|
||
<!-- Enable setting arguments from the launch file --> | ||
<xacro:arg name="prefix" default="" /> | ||
<xacro:arg name="slowdown" default="100.0" /> | ||
|
||
<!-- Import RRBot macro --> | ||
<xacro:include filename="$(find rrbot_description)/urdf/rrbot_description.urdf.xacro" /> | ||
|
||
<!-- Import Rviz colors --> | ||
<xacro:include filename="$(find rrbot_description)/gazebo/rrbot.materials.xacro" /> | ||
|
||
<!-- Import RRBot ros2_control description --> | ||
<xacro:include filename="$(find rrbot_description)/ros2_control/rrbot_transmissions_system_position_only.ros2_control.xacro" /> | ||
|
||
<!-- Used for fixing robot --> | ||
<link name="world"/> | ||
<gazebo reference="world"> | ||
<static>true</static> | ||
</gazebo> | ||
|
||
<xacro:rrbot parent="world" prefix="$(arg prefix)"> | ||
<origin xyz="0 0 0" rpy="0 0 0" /> | ||
</xacro:rrbot> | ||
|
||
<xacro:rrbot_transmissions_system_position_only | ||
name="RRBotTransmissionsSystemPositionOnly" prefix="$(arg prefix)" | ||
use_fake_hardware="$(arg use_fake_hardware)" | ||
mock_sensor_commands="$(arg mock_sensor_commands)" | ||
slowdown="$(arg slowdown)" /> | ||
|
||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.