diff --git a/clearpath_common/CHANGELOG.rst b/clearpath_common/CHANGELOG.rst index 7f94b242..1a4ce14d 100644 --- a/clearpath_common/CHANGELOG.rst +++ b/clearpath_common/CHANGELOG.rst @@ -2,66 +2,6 @@ Changelog for package clearpath_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* 0.2.4 -* Changes. -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* 0.2.1 -* Changes. -* Contributors: Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- diff --git a/clearpath_common/package.xml b/clearpath_common/package.xml index 9dbfb6af..40c11b28 100644 --- a/clearpath_common/package.xml +++ b/clearpath_common/package.xml @@ -2,7 +2,7 @@ clearpath_common - 0.3.1 + 0.2.11 Clearpath Common Metapackage Luis Camero diff --git a/clearpath_control/CHANGELOG.rst b/clearpath_control/CHANGELOG.rst index 0e3c0462..5a581cce 100644 --- a/clearpath_control/CHANGELOG.rst +++ b/clearpath_control/CHANGELOG.rst @@ -2,119 +2,6 @@ Changelog for package clearpath_control ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* Add dependency clearpath_mecanum_drive_controller -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* Add Y to controllers -* Updated wheel separation -* Keep both joint definitions -* Control updates -* Changed default canbus device to vcan0 -* Added Puma control configuration -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* Control adds manipulators if simulation -* Modifications to allow arms to function -* 0.2.6 -* Changes. -* Disable tf_frame_prefix_enable -* 0.2.5 -* Changes. -* 0.2.4 -* Changes. -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* 0.2.1 -* Changes. -* Added do150 control -* Dingo O mecanum wheels -* Fixed rocker and small covariance -* Fixed wheel radius parameter -* Initial add do100 -* Contributors: Luis Camero, Tony Baltovski, luis-camero - -* Add dependency clearpath_mecanum_drive_controller -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Add Y to controllers -* Updated wheel separation -* Keep both joint definitions -* Control updates -* Changed default canbus device to vcan0 -* Added Puma control configuration -* Control adds manipulators if simulation -* Modifications to allow arms to function -* Added do150 control -* Dingo O mecanum wheels -* Fixed rocker and small covariance -* Fixed wheel radius parameter -* Initial add do100 -* Contributors: Tony Baltovski, luis-camero, Steve Macenski, Hilary Luo, robbiefish - 0.2.11 (2024-08-08) ------------------- * Set spawner as super client diff --git a/clearpath_control/config/a200/control.yaml b/clearpath_control/config/a200/control.yaml index 194a04a4..242032bd 100644 --- a/clearpath_control/config/a200/control.yaml +++ b/clearpath_control/config/a200/control.yaml @@ -1,6 +1,6 @@ controller_manager: ros__parameters: - update_rate: 50 # Hz + update_rate: 1000 # Hz use_sim_time: False joint_state_broadcaster.type: joint_state_broadcaster/JointStateBroadcaster diff --git a/clearpath_control/launch/control.launch.py b/clearpath_control/launch/control.launch.py index 8b6e1482..b253524d 100644 --- a/clearpath_control/launch/control.launch.py +++ b/clearpath_control/launch/control.launch.py @@ -31,6 +31,7 @@ # Redistribution and use in source and binary forms, with or without # modification, is not permitted without the express permission # of Clearpath Robotics. +import os from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, GroupAction, OpaqueFunction from launch.conditions import IfCondition, UnlessCondition @@ -112,16 +113,18 @@ def launch_setup(context, *args, **kwargs): def generate_launch_description(): + home_path = os.path.expanduser('~') # Launch Configurations arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/' + default_value=PathJoinSubstitution([ + home_path, 'clearpath']) ) arg_use_sim_time = DeclareLaunchArgument( 'use_sim_time', choices=['true', 'false'], - default_value='false', + default_value='true', description='Use simulation time' ) diff --git a/clearpath_control/package.xml b/clearpath_control/package.xml index c8826cb2..5be376d7 100644 --- a/clearpath_control/package.xml +++ b/clearpath_control/package.xml @@ -2,7 +2,7 @@ clearpath_control - 0.3.1 + 0.2.11 Controllers for Clearpath Robotics platforms BSD @@ -18,7 +18,6 @@ ament_cmake - clearpath_mecanum_drive_controller controller_manager diff_drive_controller imu_filter_madgwick diff --git a/clearpath_customization/CHANGELOG.rst b/clearpath_customization/CHANGELOG.rst index 7cd7be37..21f8af34 100644 --- a/clearpath_customization/CHANGELOG.rst +++ b/clearpath_customization/CHANGELOG.rst @@ -2,92 +2,6 @@ Changelog for package clearpath_customization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* Removed author tag -* Fixed mismatched tag -* Updated package.xml to match -* Extra namespace to device launch -* Fixed URDF issues -* Fixed package and executable name -* Added customization package -* Contributors: Luis Camero, Tony Baltovski, luis-camero - -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Removed author tag -* Fixed mismatched tag -* Updated package.xml to match -* Extra namespace to device launch -* Fixed URDF issues -* Fixed package and executable name -* Added customization package -* Contributors: Luis Camero, Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- diff --git a/clearpath_customization/package.xml b/clearpath_customization/package.xml index ba599186..fe1d0e81 100644 --- a/clearpath_customization/package.xml +++ b/clearpath_customization/package.xml @@ -2,7 +2,7 @@ clearpath_customization - 0.3.1 + 0.2.11 Clearpath customization packages. Luis Camero diff --git a/clearpath_description/CHANGELOG.rst b/clearpath_description/CHANGELOG.rst index e519683f..f46cd362 100644 --- a/clearpath_description/CHANGELOG.rst +++ b/clearpath_description/CHANGELOG.rst @@ -2,92 +2,6 @@ Changelog for package clearpath_description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- -* Add manipulator dependencies -* Contributors: Luis Camero - -0.3.0 (2024-09-19) ------------------- -* Changes. -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* 0.2.4 -* Changes. -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* 0.2.1 -* Changes. -* Contributors: Tony Baltovski, luis-camero - -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Contributors: Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- diff --git a/clearpath_description/package.xml b/clearpath_description/package.xml index ad7ac2f0..a6b7bf19 100644 --- a/clearpath_description/package.xml +++ b/clearpath_description/package.xml @@ -2,7 +2,7 @@ clearpath_description - 0.3.1 + 0.2.11 Clearpath URDF descriptions metapackage Luis Camero @@ -20,7 +20,6 @@ clearpath_mounts_description clearpath_platform_description clearpath_sensors_description - clearpath_manipulators_description ament_cmake diff --git a/clearpath_generator_common/CHANGELOG.rst b/clearpath_generator_common/CHANGELOG.rst index 3e11db70..787daeed 100644 --- a/clearpath_generator_common/CHANGELOG.rst +++ b/clearpath_generator_common/CHANGELOG.rst @@ -2,123 +2,6 @@ Changelog for package clearpath_generator_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- -* Add manipulator dependencies -* Fixed linting issues for manipulator generation -* Contributors: Luis Camero - -0.3.0 (2024-09-19) ------------------- -* Changes. -* Add meshes and URDF for robotiq 2f 140 -* Standard mesh names and height parameter for tower shoulder -* R100 attachment rework -* Add Dingo plate to generator -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* 0.2.8 -* Changes. -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* 0.2.7 -* Changes. -* ARM_MOUNT to ARM_PLATE -* Linting issues -* Use if statement -* Fixed all license headers -* Fixed linting issues of collision updater node -* Pass parameters to Kinova URDF -* Updated generators to deal with grippers as part of arms -* Create control file for manipulator controller manager -* Only add manipulator controllers if simulation -* Added virtual method for manipulator launch generation -* Added semantic description generator -* Added manipulators to parameter generator -* Add manipulators to description generator -* Modifications to allow arms to function -* Added simple package writer to copy package from template -* Check terminal to set ROS_SUPER_CLIENT -* Generate script to start the discovery server -* Updated setup.bash generation for discovery server -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* switch finding meshes to use the package:// command -* 0.2.4 -* Changes. -* [clearpath_generator_common] Added package description. -* 0.2.3 -* Changes. -* Handle file paths with no directory (files in root directory of the package) -* 0.2.2 -* Changes.xx -* Enable extras urdf and meshes to be linked by package (`#53 `_) -* 0.2.1 -* Changes. -* Contributors: Hilary Luo, Luis Camero, Tony Baltovski, luis-camero - -* Add meshes and URDF for robotiq 2f 140 -* Standard mesh names and height parameter for tower shoulder -* R100 attachment rework -* Add Dingo plate to generator -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Contributors: Hilary Luo, Luis Camero, Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- * Fixes styling issues diff --git a/clearpath_generator_common/clearpath_generator_common/description/attachments.py b/clearpath_generator_common/clearpath_generator_common/description/attachments.py index c182e7e5..ac612231 100644 --- a/clearpath_generator_common/clearpath_generator_common/description/attachments.py +++ b/clearpath_generator_common/clearpath_generator_common/description/attachments.py @@ -33,12 +33,7 @@ from clearpath_config.platform.attachments.a200 import A200Attachment from clearpath_config.platform.attachments.config import BaseAttachment -from clearpath_config.platform.attachments.dd100 import DD100Attachment -from clearpath_config.platform.attachments.dd150 import DD150Attachment -from clearpath_config.platform.attachments.do100 import DO100Attachment -from clearpath_config.platform.attachments.do150 import DO150Attachment from clearpath_config.platform.attachments.j100 import J100Attachment -from clearpath_config.platform.attachments.r100 import R100Attachment from clearpath_config.platform.attachments.w200 import W200Attachment from clearpath_config.platform.types.bumper import Bumper @@ -79,46 +74,6 @@ def __init__(self, attachment: Bumper) -> None: self.EXTENSION: attachment.extension }) - class DingoTopPlateDescription(BaseDescription): - HEIGHT = 'height' - - def __init__(self, attachment: BaseAttachment) -> None: - super().__init__(attachment) - self.parameters.update({ - self.HEIGHT: attachment.height - }) - - class RidgebackFAMSDescription(BaseDescription): - TABLE_HEIGHT = 'table_height' - - def __init__(self, attachment: BaseAttachment) -> None: - super().__init__(attachment) - self.parameters.update({ - self.TABLE_HEIGHT: attachment.table_height - }) - - class RidgebackHAMSDescription(BaseDescription): - TABLE_HEIGHT = 'table_height' - MOUNT_HEIGHT = 'mount_height' - - def __init__(self, attachment: BaseAttachment) -> None: - super().__init__(attachment) - self.parameters.update({ - self.TABLE_HEIGHT: attachment.table_height, - self.MOUNT_HEIGHT: attachment.mount_height - }) - - class RidgebackTowerDescription(BaseDescription): - LEFT_HEIGHT = 'left_height' - RIGHT_HEIGHT = 'right_height' - - def __init__(self, attachment: BaseAttachment) -> None: - super().__init__(attachment) - self.parameters.update({ - self.LEFT_HEIGHT: attachment.left_height, - self.RIGHT_HEIGHT: attachment.right_height - }) - MODEL = { # A200 A200Attachment.BUMPER: BumperDescription, @@ -131,15 +86,6 @@ def __init__(self, attachment: BaseAttachment) -> None: W200Attachment.GENERATOR: BaseDescription, W200Attachment.BULKHEAD: BaseDescription, W200Attachment.ARM_PLATE: BaseDescription, - # DD100 - DD100Attachment.TOP_PLATE: DingoTopPlateDescription, - DD150Attachment.TOP_PLATE: DingoTopPlateDescription, - DO100Attachment.TOP_PLATE: DingoTopPlateDescription, - DO150Attachment.TOP_PLATE: DingoTopPlateDescription, - # R100 - R100Attachment.FAMS: RidgebackFAMSDescription, - R100Attachment.HAMS: RidgebackHAMSDescription, - R100Attachment.TOWER: RidgebackTowerDescription, } def __new__(cls, attachment: BaseAttachment) -> BaseDescription: diff --git a/clearpath_generator_common/clearpath_generator_common/description/manipulators.py b/clearpath_generator_common/clearpath_generator_common/description/manipulators.py index dc0ff2d0..2b40fba0 100644 --- a/clearpath_generator_common/clearpath_generator_common/description/manipulators.py +++ b/clearpath_generator_common/clearpath_generator_common/description/manipulators.py @@ -29,8 +29,6 @@ # Redistribution and use in source and binary forms, with or without # modification, is not permitted without the express permission # of Clearpath Robotics. -from typing import List - from clearpath_config.manipulators.types.arms import ( BaseArm, KinovaGen3Dof6, @@ -44,6 +42,8 @@ ) from clearpath_config.manipulators.types.manipulator import BaseManipulator +from typing import List + class ManipulatorDescription(): @@ -97,7 +97,7 @@ class KinovaArmDescription(ArmDescription): GRIPPER_COMM = 'use_internal_bus_gripper_comm' GRIPPER_NAMES = { Kinova2FLite.get_manipulator_model(): '_right_finger_bottom_joint', - Robotiq2F140.get_manipulator_model(): '_finger_joint', + Robotiq2F140.get_manipulator_model(): '_robotiq_85_left_knuckle_joint', Robotiq2F85.get_manipulator_model(): '_robotiq_85_left_knuckle_joint', } diff --git a/clearpath_generator_common/clearpath_generator_common/launch/generator.py b/clearpath_generator_common/clearpath_generator_common/launch/generator.py index 4442ef01..81d680b5 100644 --- a/clearpath_generator_common/clearpath_generator_common/launch/generator.py +++ b/clearpath_generator_common/clearpath_generator_common/launch/generator.py @@ -97,7 +97,7 @@ def __init__(self, ) def generate(self) -> None: - self.generate_manipulators() + #self.generate_manipulators() self.generate_sensors() self.generate_platform() diff --git a/clearpath_generator_common/clearpath_generator_common/param/manipulators.py b/clearpath_generator_common/clearpath_generator_common/param/manipulators.py index d9dd6def..7da0fffd 100644 --- a/clearpath_generator_common/clearpath_generator_common/param/manipulators.py +++ b/clearpath_generator_common/clearpath_generator_common/param/manipulators.py @@ -32,7 +32,7 @@ import os from clearpath_config.clearpath_config import ClearpathConfig -from clearpath_config.common.utils.dictionary import merge_dict, replace_dict_items +from clearpath_config.common.utils.dictionary import replace_dict_items, merge_dict from clearpath_generator_common.common import MoveItParamFile, Package, ParamFile from clearpath_generator_common.param.writer import ParamWriter @@ -92,7 +92,7 @@ def generate_parameters(self, use_sim_time: bool = False) -> None: # Arm Control Parameter File arm_param_file = ParamFile( name='control', - package=Package('clearpath_manipulators_description'), + package=Package("clearpath_manipulators_description"), path='config/%s/%s' % ( arm.get_manipulator_type(), arm.get_manipulator_model()), @@ -113,7 +113,7 @@ def generate_parameters(self, use_sim_time: bool = False) -> None: # Gripper Control Parameter File gripper_param_file = ParamFile( name='control', - package=Package('clearpath_manipulators_description'), + package=Package("clearpath_manipulators_description"), path='config/%s/%s' % ( gripper.get_manipulator_type(), gripper.get_manipulator_model()), diff --git a/clearpath_generator_common/clearpath_generator_common/param/platform.py b/clearpath_generator_common/clearpath_generator_common/param/platform.py index 54d6959d..2c267806 100644 --- a/clearpath_generator_common/clearpath_generator_common/param/platform.py +++ b/clearpath_generator_common/clearpath_generator_common/param/platform.py @@ -109,9 +109,9 @@ def generate_parameters(self, use_sim_time: bool = False) -> None: for arm in self.clearpath_config.manipulators.get_all_arms(): # Arm Control Parameter File arm_param_file = ParamFile( - name='control', - package=Package('clearpath_manipulators_description'), - path='config/%s/%s' % ( + name="control", + package=Package("clearpath_manipulators_description"), + path="config/%s/%s" % ( arm.get_manipulator_type(), arm.get_manipulator_model()), parameters={} @@ -132,9 +132,9 @@ def generate_parameters(self, use_sim_time: bool = False) -> None: gripper = arm.gripper # Gripper Control Parameter File gripper_param_file = ParamFile( - name='control', - package=Package('clearpath_manipulators_description'), - path='config/%s/%s' % ( + name="control", + package=Package("clearpath_manipulators_description"), + path="config/%s/%s" % ( gripper.get_manipulator_type(), gripper.get_manipulator_model()), parameters={} diff --git a/clearpath_generator_common/clearpath_generator_common/semantic_description/generator.py b/clearpath_generator_common/clearpath_generator_common/semantic_description/generator.py index 66a61e28..4b75a740 100644 --- a/clearpath_generator_common/clearpath_generator_common/semantic_description/generator.py +++ b/clearpath_generator_common/clearpath_generator_common/semantic_description/generator.py @@ -37,7 +37,6 @@ class SemanticDescriptionGenerator(BaseGenerator): - def __init__(self, setup_path: str = '/etc/clearpath/') -> None: super().__init__(setup_path) self.xacro_writer = XacroWriter(self.setup_path, self.serial_number, '.srdf.xacro') diff --git a/clearpath_generator_common/package.xml b/clearpath_generator_common/package.xml index 1f5c37ea..346f90aa 100644 --- a/clearpath_generator_common/package.xml +++ b/clearpath_generator_common/package.xml @@ -2,7 +2,7 @@ clearpath_generator_common - 0.3.1 + 0.2.11 Clearpath Common Generator Luis Camero Roni Kreinin @@ -18,7 +18,6 @@ clearpath_control clearpath_description clearpath_platform - clearpath_manipulators ament_lint_auto ament_lint_common diff --git a/clearpath_manipulators/CHANGELOG.rst b/clearpath_manipulators/CHANGELOG.rst deleted file mode 100644 index d183b611..00000000 --- a/clearpath_manipulators/CHANGELOG.rst +++ /dev/null @@ -1,101 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package clearpath_manipulators -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Fixed package version on new packages to match old packages. -* Changes. -* Fixed all license headers -* Added MoveIt to manipulation service launch -* Removed old ompl -* Added '_' to omp to make it always first alphabetically -* Added all chomp parameters explicitly to config -* Renamed manipulators package -* Contributors: Luis Camero, Tony Baltovski - -* Fixed all license headers -* Added MoveIt to manipulation service launch -* Removed old ompl -* Added '_' to omp to make it always first alphabetically -* Added all chomp parameters explicitly to config -* Renamed manipulators package -* Contributors: Luis Camero - -0.2.11 (2024-08-08) -------------------- - -0.2.10 (2024-07-25) -------------------- - -0.2.9 (2024-05-28) ------------------- - -0.2.8 (2024-05-14) ------------------- - -0.2.7 (2024-04-08) ------------------- - -0.2.6 (2024-01-18) ------------------- - -0.2.5 (2024-01-15) ------------------- - -0.2.4 (2024-01-11) ------------------- - -0.2.3 (2024-01-08) ------------------- - -0.2.2 (2024-01-04) ------------------- - -0.2.1 (2023-12-21) ------------------- - -0.2.0 (2023-12-08) ------------------- - -0.1.3 (2023-11-03) ------------------- - -0.1.2 (2023-10-02) ------------------- - -0.1.1 (2023-08-25) ------------------- - -0.1.0 (2023-08-17) ------------------- - -0.0.9 (2023-07-31) ------------------- - -0.0.8 (2023-07-24) ------------------- - -0.0.7 (2023-07-19) ------------------- - -0.0.6 (2023-07-13) ------------------- - -0.0.5 (2023-07-12) ------------------- - -0.0.4 (2023-07-07) ------------------- - -0.0.3 (2023-07-05) ------------------- - -0.0.2 (2023-07-04) ------------------- - -0.0.1 (2023-06-21) ------------------- diff --git a/clearpath_manipulators/CMakeLists.txt b/clearpath_manipulators/CMakeLists.txt index ad45a65a..24ec31e9 100644 --- a/clearpath_manipulators/CMakeLists.txt +++ b/clearpath_manipulators/CMakeLists.txt @@ -2,6 +2,40 @@ cmake_minimum_required(VERSION 3.5) project(clearpath_manipulators) find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(trajectory_msgs REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(control_msgs REQUIRED) + +# Include directories +include_directories(include) + +# Add the executables for your nodes +add_executable(gazebo_to_real_robot_node src/gazebo_to_real_robot_node.cpp) +add_executable(gazebo_to_real_gripper_node src/gazebo_to_real_gripper_node.cpp) + +# Link against required libraries +ament_target_dependencies(gazebo_to_real_robot_node + rclcpp + sensor_msgs + trajectory_msgs +) + +ament_target_dependencies(gazebo_to_real_gripper_node + rclcpp + sensor_msgs + control_msgs + rclcpp_action +) + +# Install the executables +install(TARGETS + gazebo_to_real_robot_node + gazebo_to_real_gripper_node + DESTINATION lib/${PROJECT_NAME} +) + install(DIRECTORY config launch DESTINATION share/${PROJECT_NAME} ) diff --git a/clearpath_manipulators/config/planning/_ompl/defaults.yaml b/clearpath_manipulators/config/planning/_ompl/defaults.yaml index dda05494..fd285d12 100644 --- a/clearpath_manipulators/config/planning/_ompl/defaults.yaml +++ b/clearpath_manipulators/config/planning/_ompl/defaults.yaml @@ -127,3 +127,30 @@ planner_configs: sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 max_failures: 5000 # maximum consecutive failure limit. default: 5000 +arm_0: + default_planner_config: RRTConnect + planner_configs: + - AnytimePathShortening + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo \ No newline at end of file diff --git a/clearpath_manipulators/config/planning_scene.yaml b/clearpath_manipulators/config/planning_scene.yaml index 27c248bf..c8ac5ba6 100644 --- a/clearpath_manipulators/config/planning_scene.yaml +++ b/clearpath_manipulators/config/planning_scene.yaml @@ -1,5 +1,5 @@ publish_planning_scene: True -publish_robot_description: False +publish_robot_description: True publish_robot_description_semantic: True publish_geometry_updates: True publish_state_updates: True diff --git a/clearpath_manipulators/launch/control.launch.py b/clearpath_manipulators/launch/control.launch.py index 260cea32..f07dc3b1 100644 --- a/clearpath_manipulators/launch/control.launch.py +++ b/clearpath_manipulators/launch/control.launch.py @@ -31,6 +31,7 @@ # Redistribution and use in source and binary forms, with or without # modification, is not permitted without the express permission # of Clearpath Robotics. +import os from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, GroupAction, OpaqueFunction from launch.substitutions import LaunchConfiguration, PathJoinSubstitution @@ -100,10 +101,12 @@ def launch_setup(context, *args, **kwargs): def generate_launch_description(): + home_path = os.path.expanduser('~') # Launch Configurations arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/' + default_value=PathJoinSubstitution([ + home_path, 'clearpath']) ) arg_namespace = DeclareLaunchArgument( diff --git a/clearpath_manipulators/launch/manipulators.launch.py b/clearpath_manipulators/launch/manipulators.launch.py index b07d51a6..472633b8 100644 --- a/clearpath_manipulators/launch/manipulators.launch.py +++ b/clearpath_manipulators/launch/manipulators.launch.py @@ -31,6 +31,7 @@ # Redistribution and use in source and binary forms, with or without # modification, is not permitted without the express permission # of Clearpath Robotics. +import os from launch import LaunchDescription from launch.actions import ( DeclareLaunchArgument, @@ -49,6 +50,7 @@ def generate_launch_description(): + home_path = os.path.expanduser('~') # Packages pkg_clearpath_manipulators_description = FindPackageShare('clearpath_manipulators_description') pkg_clearpath_manipulators = FindPackageShare('clearpath_manipulators') @@ -56,13 +58,14 @@ def generate_launch_description(): # Launch Arguments arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/' + default_value=PathJoinSubstitution([ + home_path, 'clearpath']) ) arg_use_sim_time = DeclareLaunchArgument( 'use_sim_time', choices=['true', 'false'], - default_value='false', + default_value='true', description='Use simulation time' ) @@ -95,7 +98,7 @@ def generate_launch_description(): group_manipulators_action = GroupAction( actions=[ - PushRosNamespace(PathJoinSubstitution([namespace, 'manipulators'])), + PushRosNamespace(PathJoinSubstitution([namespace, 'a200_0000'])), IncludeLaunchDescription( PythonLaunchDescriptionSource(launch_file_manipulators_description), launch_arguments=[ @@ -106,14 +109,14 @@ def generate_launch_description(): ), # Launch clearpath_control/control.launch.py which is just robot_localization. - IncludeLaunchDescription( - PythonLaunchDescriptionSource(launch_file_control), - launch_arguments=[ - ('namespace', namespace), - ('setup_path', setup_path), - ('use_sim_time', use_sim_time), - ] - ), +# IncludeLaunchDescription( +# PythonLaunchDescriptionSource(launch_file_control), +# launch_arguments=[ +# ('namespace', namespace), +# ('setup_path', setup_path), +# ('use_sim_time', use_sim_time), +# ] +# ), ] ) diff --git a/clearpath_manipulators/launch/moveit.launch.py b/clearpath_manipulators/launch/moveit.launch.py index 2bcd6430..6544ab74 100644 --- a/clearpath_manipulators/launch/moveit.launch.py +++ b/clearpath_manipulators/launch/moveit.launch.py @@ -35,18 +35,20 @@ import xacro from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, OpaqueFunction -from launch.substitutions import LaunchConfiguration +from launch.actions import DeclareLaunchArgument, OpaqueFunction, TimerAction +from launch.substitutions import LaunchConfiguration, PathJoinSubstitution from launch_ros.actions import Node from clearpath_config.clearpath_config import ClearpathConfig + def launch_setup(context, *args, **kwargs): # Launch Configurations setup_path = LaunchConfiguration('setup_path') use_sim_time = LaunchConfiguration('use_sim_time') setup_path_context = setup_path.perform(context) + rviz_config_file = '/home/aalmrad/demos/clearpath_kinova/clearpath_ws/src/clearpath_common/clearpath_moveit_config/config/moveit.rviz' # Namespace namespace = ClearpathConfig( @@ -66,9 +68,9 @@ def launch_setup(context, *args, **kwargs): os.path.join(setup_path_context, 'robot.srdf') ).toxml() } - - return [ - Node( + + #Moveit node + moveit_node = Node( package='moveit_ros_move_group', executable='move_group', output='log', @@ -85,18 +87,41 @@ def launch_setup(context, *args, **kwargs): ('joint_states', 'platform/joint_states'), ] ) - ] + + # RViz Node (with delay) + rviz_node = TimerAction( + period=5.0, # Delay of 5 seconds (adjust as needed) + actions=[ + Node( + package='rviz2', + executable='rviz2', + output='log', + namespace=namespace, + arguments=['-d', rviz_config_file], + remappings=[ + ('/tf', 'tf'), + ('/tf_static', 'tf_static'), + ('joint_states', 'platform/joint_states'), + ] + ) + ] + ) + + return [moveit_node, rviz_node] def generate_launch_description(): + + home_path = os.path.expanduser('~') arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/', + default_value=PathJoinSubstitution([ + home_path, 'clearpath']), description='Clearpath setup path' ) arg_use_sim_time = DeclareLaunchArgument( 'use_sim_time', - default_value='false', + default_value='true', choices=['true', 'false'], description='use_sim_time' ) diff --git a/clearpath_manipulators/package.xml b/clearpath_manipulators/package.xml index 22b91f81..6787d525 100644 --- a/clearpath_manipulators/package.xml +++ b/clearpath_manipulators/package.xml @@ -2,7 +2,7 @@ clearpath_manipulators - 0.3.1 + 0.2.6 MoveIt configuration built around Clearpath Configuration Luis Camero @@ -25,6 +25,11 @@ position_controllers tf2_ros xacro + rclcpp + sensor_msgs + trajectory_msgs + rclcpp_action + control_msgs ament_cmake diff --git a/clearpath_manipulators/src/gazebo_to_real_gripper_node.cpp b/clearpath_manipulators/src/gazebo_to_real_gripper_node.cpp new file mode 100644 index 00000000..67e9e9b1 --- /dev/null +++ b/clearpath_manipulators/src/gazebo_to_real_gripper_node.cpp @@ -0,0 +1,104 @@ +#include +#include +#include +#include +#include + +class GripperSyncNode : public rclcpp::Node +{ +public: + using GripperCommand = control_msgs::action::GripperCommand; + + GripperSyncNode() + : Node("gazebo_to_real_gripper_bridge") + { + // Initialize the action client for the real-life gripper + real_gripper_client_ = rclcpp_action::create_client(this, "/robotiq_gripper_controller/gripper_cmd"); + + // Initialize the subscription to the simulated robot's joint states + joint_state_sub_ = this->create_subscription( + "/a200_0000/platform/joint_states", 10, + std::bind(&GripperSyncNode::jointStateCallback, this, std::placeholders::_1)); + + // Wait for the action server to become available + if (!real_gripper_client_->wait_for_action_server(std::chrono::seconds(5))) + { + RCLCPP_ERROR(this->get_logger(), "Real gripper action server not available."); + } + else + { + RCLCPP_INFO(this->get_logger(), "Real gripper action server connected."); + } + + RCLCPP_INFO(this->get_logger(), "Gripper sync node started."); + } + +private: + rclcpp::Subscription::SharedPtr joint_state_sub_; + rclcpp_action::Client::SharedPtr real_gripper_client_; + + void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr msg) + { + //rclcpp::sleep_for(std::chrono::milliseconds(1000)); + // Find the index of the 'robotiq_85_left_knuckle_joint' + auto it = std::find(msg->name.begin(), msg->name.end(), "robotiq_85_left_knuckle_joint"); + if (it != msg->name.end()) + { + int index = std::distance(msg->name.begin(), it); + double joint_position = msg->position[index]; + sendGripperCommand(joint_position); + } + else + { + RCLCPP_WARN(this->get_logger(), "Joint 'robotiq_85_left_knuckle_joint' not found."); + } + } + + void sendGripperCommand(double position) + { + // Prepare the gripper command goal + auto goal_msg = GripperCommand::Goal(); + goal_msg.command.position = position; // Map joint position directly to the gripper command + goal_msg.command.max_effort = 100.0; + + //rclcpp_action::Client::SendGoalOptions send_goal_options; + + // Active callback for goal response + /* + send_goal_options.goal_response_callback = + [this](const rclcpp_action::Client::GoalHandle::SharedPtr& goal_handle) { + if (!goal_handle) + { + RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server."); + } + else + { + RCLCPP_INFO(this->get_logger(), "Gripper command sent successfully."); + } + }; + */ + // Result callback for goal completion + /* + send_goal_options.result_callback = + [this](const rclcpp_action::ClientGoalHandle::WrappedResult & result) { + if (result.code == rclcpp_action::ResultCode::SUCCEEDED) { + RCLCPP_INFO(this->get_logger(), "Gripper command succeeded."); + } else { + RCLCPP_ERROR(this->get_logger(), "Gripper command failed with code: %d", result.code); + } + }; + */ + + // Send the goal to the real gripper + real_gripper_client_->async_send_goal(goal_msg); + } +}; + +int main(int argc, char **argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/clearpath_manipulators/src/gazebo_to_real_robot_node.cpp b/clearpath_manipulators/src/gazebo_to_real_robot_node.cpp new file mode 100644 index 00000000..e3320580 --- /dev/null +++ b/clearpath_manipulators/src/gazebo_to_real_robot_node.cpp @@ -0,0 +1,173 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include // For std::abs +#include + +class GazeboToRealRobotBridge : public rclcpp::Node +{ +public: + GazeboToRealRobotBridge() + : Node("gazebo_to_real_robot_bridge") + { + real_arm_joint_positions_.resize(7, 0.0); + // Subscribe to the Gazebo joint states + gazebo_sub_ = this->create_subscription( + "/a200_0000/platform/joint_states", 10, + std::bind(&GazeboToRealRobotBridge::gazebo_joint_states_callback, this, std::placeholders::_1)); + // Set the QoS profile for the publisher to match the expected settings + rclcpp::QoS qos_profile = rclcpp::QoS(10) + .reliable() // Reliable QoS + .durability_volatile(); // Volatile durability + + // Subscribe to the /joint_states topic + joint_state_sub_ = this->create_subscription( + "/joint_states", 10, + std::bind(&GazeboToRealRobotBridge::joint_state_callback, this, std::placeholders::_1)); + + // Publisher for the physical robot's joint trajectory controller + robot_pub_ = this->create_publisher( + "/joint_trajectory_controller/joint_trajectory", qos_profile); + + // Define the arm joint names you're interested in + sim_arm_joint_names_ = { + "arm_0_joint_1", + "arm_0_joint_2", + "arm_0_joint_3", + "arm_0_joint_4", + "arm_0_joint_5", + "arm_0_joint_6", + "arm_0_joint_7"}; + real_arm_joint_names_ = { + "joint_1", + "joint_2", + "joint_3", + "joint_4", + "joint_5", + "joint_6", + "joint_7" + }; + } + +private: + + + // Callback function to handle the incoming joint states from Gazebo + void gazebo_joint_states_callback(const sensor_msgs::msg::JointState::SharedPtr msg) + { + std::lock_guard lock(joint_positions_mutex); // Lock the mutex to prevent race conditions + if(!init_reached){ + rclcpp::sleep_for(std::chrono::milliseconds(1000)); + } + + trajectory_msgs::msg::JointTrajectory traj_msg; + traj_msg.joint_names = real_arm_joint_names_; + + trajectory_msgs::msg::JointTrajectoryPoint traj_point; + + // Filter only the arm joint positions from the incoming JointState message + for (const auto &sim_arm_joint_name : sim_arm_joint_names_) + { + auto it = std::find(msg->name.begin(), msg->name.end(), sim_arm_joint_name); + if (it != msg->name.end()) + { + // Get the index of the arm joint in the message + auto index = std::distance(msg->name.begin(), it); + + // Append the corresponding position to the trajectory point + traj_point.positions.push_back(msg->position[index]); + } + } + if(!init_reached){ + // Calculate the time from start based on the difference between real and simulated joint positions + double max_position_difference = 0.0; + + for (size_t i = 0; i < traj_point.positions.size(); ++i) + { + // Calculate the absolute difference between real and simulated joint positions + double position_difference = std::abs(traj_point.positions[i] - real_arm_joint_positions_[i]); + if (position_difference > max_position_difference) { + max_position_difference = position_difference; // Track the maximum difference + std::cout << "Max position difference: " << max_position_difference << std::endl; + } + } + if (max_position_difference <= tol){ + std::cout << "Robot sync with the simulation initial position reached!" << std::endl; + init_reached = true; + } + + // Define a scaling factor for time (adjust this value as necessary) + double scaling_factor = 3.0; // This controls how much time is given based on the max difference + + // Calculate time based on the difference + double total_time = max_position_difference * scaling_factor; + // Set time_from_start based on the maximum position difference + traj_point.time_from_start.sec = static_cast(total_time); + traj_point.time_from_start.nanosec = static_cast((total_time - traj_point.time_from_start.sec) * 1e9); + + + } + else{ + traj_point.time_from_start.sec = 0; + } + + // Add the trajectory point to the message + traj_msg.points.push_back(traj_point); + + // Publish the trajectory message to the physical robot + robot_pub_->publish(traj_msg); + } + + // Callback function to handle joint state messages coming from the rl robot + void joint_state_callback(const sensor_msgs::msg::JointState::SharedPtr msg) + { + std::lock_guard lock(joint_positions_mutex); // Lock the mutex to prevent race conditions + + // Ensure that real_arm_joint_positions_ has the correct size (already resized) + real_arm_joint_positions_.clear(); + real_arm_joint_positions_.resize(real_arm_joint_names_.size(), 0.0); + + + // Loop through the real_arm_joint_names_ and update the corresponding positions directly + for (size_t i = 0; i < real_arm_joint_names_.size(); ++i) + { + auto it = std::find(msg->name.begin(), msg->name.end(), real_arm_joint_names_[i]); + if (it != msg->name.end()) + { + // Get the index of the arm joint in the message + auto index = std::distance(msg->name.begin(), it); + + // Assign the corresponding position directly to the vector + real_arm_joint_positions_[i] = msg->position[index]; + } + } + } + + rclcpp::Subscription::SharedPtr gazebo_sub_; + rclcpp::Subscription::SharedPtr joint_state_sub_; + rclcpp::Publisher::SharedPtr robot_pub_; + + // List of arm joint names you're interested in + std::vector real_arm_joint_names_; + std::vector sim_arm_joint_names_; + // Vector to store the real-life robot's joints positions + std::vector real_arm_joint_positions_; + // Mutex to protect access to real_arm_joint_positions_ + std::mutex joint_positions_mutex; + bool init_reached = false; + double tol = 0.01; +}; + +int main(int argc, char **argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node); + rclcpp::shutdown(); + return 0; +} diff --git a/clearpath_manipulators_description/CHANGELOG.rst b/clearpath_manipulators_description/CHANGELOG.rst deleted file mode 100644 index 81c0eb15..00000000 --- a/clearpath_manipulators_description/CHANGELOG.rst +++ /dev/null @@ -1,111 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package clearpath_manipulators_description -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Fixed package version on new packages to match old packages. -* Changes. -* Add meshes and URDF for robotiq 2f 140 -* Fixed all license headers -* Added dependencies to manipulators description -* Added Robotiq grippers for Kinova -* Added all joints to the Kinova gripper SRDF -* Removed unecessary parameter -* Gripper joint set through arm URD -* Added another variable to add namespace for MoveItt -* Added argument to toggle manipulator controllers -* Manipulator description to match platform description launch -* Added all descriptions for kinova manipulators -* Contributors: Luis Camero, Tony Baltovski - -* Add meshes and URDF for robotiq 2f 140 -* Fixed all license headers -* Added dependencies to manipulators description -* Added Robotiq grippers for Kinova -* Added all joints to the Kinova gripper SRDF -* Removed unecessary parameter -* Gripper joint set through arm URD -* Added another variable to add namespace for MoveItt -* Added argument to toggle manipulator controllers -* Manipulator description to match platform description launch -* Added all descriptions for kinova manipulators -* Contributors: Luis Camero - -0.2.11 (2024-08-08) -------------------- - -0.2.10 (2024-07-25) -------------------- - -0.2.9 (2024-05-28) ------------------- - -0.2.8 (2024-05-14) ------------------- - -0.2.7 (2024-04-08) ------------------- - -0.2.6 (2024-01-18) ------------------- - -0.2.5 (2024-01-15) ------------------- - -0.2.4 (2024-01-11) ------------------- - -0.2.3 (2024-01-08) ------------------- - -0.2.2 (2024-01-04) ------------------- - -0.2.1 (2023-12-21) ------------------- - -0.2.0 (2023-12-08) ------------------- - -0.1.3 (2023-11-03) ------------------- - -0.1.2 (2023-10-02) ------------------- - -0.1.1 (2023-08-25) ------------------- - -0.1.0 (2023-08-17) ------------------- - -0.0.9 (2023-07-31) ------------------- - -0.0.8 (2023-07-24) ------------------- - -0.0.7 (2023-07-19) ------------------- - -0.0.6 (2023-07-13) ------------------- - -0.0.5 (2023-07-12) ------------------- - -0.0.4 (2023-07-07) ------------------- - -0.0.3 (2023-07-05) ------------------- - -0.0.2 (2023-07-04) ------------------- - -0.0.1 (2023-06-21) ------------------- diff --git a/clearpath_manipulators_description/CMakeLists.txt b/clearpath_manipulators_description/CMakeLists.txt index c0a67284..804986bd 100644 --- a/clearpath_manipulators_description/CMakeLists.txt +++ b/clearpath_manipulators_description/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.5) project(clearpath_manipulators_description) find_package(ament_cmake REQUIRED) -install(DIRECTORY urdf config srdf launch meshes +install(DIRECTORY urdf config srdf launch DESTINATION share/${PROJECT_NAME} ) diff --git a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/control.yaml b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/control.yaml index 4a840e5c..7f2d6853 100644 --- a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/control.yaml +++ b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/control.yaml @@ -7,6 +7,9 @@ controller_manager: ${name}_joint_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController + robotiq_85_controller: + type: position_controllers/GripperActionController + ${name}_joint_trajectory_controller: ros__parameters: @@ -30,3 +33,9 @@ ${name}_joint_trajectory_controller: constraints: stopped_velocity_tolerance: 0.0 goal_time: 0.0 + +robotiq_85_controller: + ros__parameters: + default: true + joint: robotiq_85_left_knuckle_joint + allow_stalling: true diff --git a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/initial_positions.yaml b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/initial_positions.yaml index b010d6d8..31bf8898 100644 --- a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/initial_positions.yaml +++ b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/initial_positions.yaml @@ -1,10 +1,11 @@ # Default initial positions for robot's ros2_control fake system initial_positions: - ${name}_joint_1: 0 - ${name}_joint_2: 0 - ${name}_joint_3: 0 - ${name}_joint_4: 0 - ${name}_joint_5: 0 - ${name}_joint_6: 0 - ${name}_joint_7: 0 + ${name}_joint_1: -0.23921483 + ${name}_joint_2: 0.85088292 + ${name}_joint_3: 0.1007404 + ${name}_joint_4: 2.40223628 + ${name}_joint_5: -0.07318166 + ${name}_joint_6: -1.70646077 + ${name}_joint_7: -1.63699667 + robotiq_85_left_knuckle_joint: 0.0 diff --git a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/joint_limits.yaml b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/joint_limits.yaml index 1f659281..24828b3c 100644 --- a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/joint_limits.yaml +++ b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/joint_limits.yaml @@ -43,3 +43,9 @@ joint_limits: max_velocity: 0.8727 has_acceleration_limits: true max_acceleration: 10.0 + robotiq_85_left_knuckle_joint: + has_velocity_limits: true + max_velocity: 0.5 + has_acceleration_limits: true + max_acceleration: 1.0 + diff --git a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/moveit_controllers.yaml b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/moveit_controllers.yaml index b72e5235..09911d9c 100644 --- a/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/moveit_controllers.yaml +++ b/clearpath_manipulators_description/config/arm/kinova_gen3_7dof/moveit_controllers.yaml @@ -4,9 +4,10 @@ moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControll moveit_simple_controller_manager: controller_names: - - ${controller_name}_joint_trajectory_controller + - ${name}_joint_trajectory_controller + - robotiq_85_controller - ${controller_name}_joint_trajectory_controller: + ${name}_joint_trajectory_controller: type: FollowJointTrajectory action_ns: follow_joint_trajectory default: true @@ -18,3 +19,10 @@ moveit_simple_controller_manager: - ${name}_joint_5 - ${name}_joint_6 - ${name}_joint_7 + + robotiq_85_controller: + type: GripperCommand + joints: + - robotiq_85_left_knuckle_joint + action_ns: gripper_cmd + default: true diff --git a/clearpath_manipulators_description/launch/description.launch.py b/clearpath_manipulators_description/launch/description.launch.py index 4e796161..d710b648 100644 --- a/clearpath_manipulators_description/launch/description.launch.py +++ b/clearpath_manipulators_description/launch/description.launch.py @@ -29,6 +29,7 @@ # Redistribution and use in source and binary forms, with or without # modification, is not permitted without the express permission # of Clearpath Robotics. +import os from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import (Command, FindExecutable, @@ -43,11 +44,13 @@ def generate_launch_description(): robot_description_command = LaunchConfiguration('robot_description_command') use_sim_time = LaunchConfiguration('use_sim_time') namespace = LaunchConfiguration('namespace') + home_path = os.path.expanduser('~') # Launch Arguments arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/' + default_value=PathJoinSubstitution([ + home_path, 'clearpath']) ) arg_namespace = DeclareLaunchArgument( @@ -69,7 +72,7 @@ def generate_launch_description(): robot_urdf, ' ', 'is_sim:=', - use_sim_time, + 'true', ' ', 'namespace:=', namespace, @@ -88,7 +91,7 @@ def generate_launch_description(): arg_use_sim_time = DeclareLaunchArgument( 'use_sim_time', choices=['true', 'false'], - default_value='false', + default_value='true', description='Use simulation time' ) diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_base_link.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_base_link.stl deleted file mode 100644 index d0f3a2ca..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_base_link.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_base_link_collision.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_base_link_collision.stl deleted file mode 100644 index 7eccbbbe..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_base_link_collision.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_coupling.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_coupling.stl deleted file mode 100644 index 02c600fe..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_coupling.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_coupling_collision.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_coupling_collision.stl deleted file mode 100644 index 3afb3826..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_coupling_collision.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_finger.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_finger.stl deleted file mode 100644 index ad723f3d..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_finger.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_finger_collision.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_finger_collision.stl deleted file mode 100644 index 4eb5a1fa..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_finger_collision.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_knuckle.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_knuckle.stl deleted file mode 100644 index 616da3d3..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_knuckle.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_knuckle_collision.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_knuckle_collision.stl deleted file mode 100644 index 49e8169d..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_inner_knuckle_collision.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_finger.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_finger.stl deleted file mode 100644 index 64301c5f..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_finger.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_finger_collision.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_finger_collision.stl deleted file mode 100644 index 046135f2..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_finger_collision.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_knuckle.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_knuckle.stl deleted file mode 100644 index 9621fc84..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_knuckle.stl and /dev/null differ diff --git a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_knuckle_collision.stl b/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_knuckle_collision.stl deleted file mode 100644 index 2d53aa7c..00000000 Binary files a/clearpath_manipulators_description/meshes/gripper/robotiq_2f_140_outer_knuckle_collision.stl and /dev/null differ diff --git a/clearpath_manipulators_description/package.xml b/clearpath_manipulators_description/package.xml index e89e51e8..45d2621a 100644 --- a/clearpath_manipulators_description/package.xml +++ b/clearpath_manipulators_description/package.xml @@ -2,7 +2,7 @@ clearpath_manipulators_description - 0.3.1 + 0.2.6 Clearpath manipulator URDF descriptions Luis Camero diff --git a/clearpath_manipulators_description/urdf/arm/kinova_gen3_7dof.urdf.xacro b/clearpath_manipulators_description/urdf/arm/kinova_gen3_7dof.urdf.xacro index 11fcd163..1a1ac89d 100644 --- a/clearpath_manipulators_description/urdf/arm/kinova_gen3_7dof.urdf.xacro +++ b/clearpath_manipulators_description/urdf/arm/kinova_gen3_7dof.urdf.xacro @@ -1,8 +1,8 @@ - + - + + initial_positions:=${dict(joint_1=-0.23921483,joint_2=0.85088292,joint_3=0.1007404,joint_4=2.40223628,joint_5=-0.07318166,joint_6=-1.70646077,joint_7=-1.63699667)}"> @@ -97,6 +97,7 @@ upper="${2*PI}" effort="39" velocity="1.3963" /> + @@ -113,6 +114,7 @@ + @@ -148,6 +150,7 @@ + @@ -187,6 +190,7 @@ upper="${2*PI}" effort="39" velocity="1.3963" /> + @@ -203,6 +207,7 @@ + @@ -238,6 +243,7 @@ + @@ -277,6 +283,7 @@ upper="${2*PI}" effort="9" velocity="1.2218" /> + @@ -291,8 +298,9 @@ + @@ -327,7 +335,8 @@ link="${name}_spherical_wrist_2_link" /> - + + @@ -394,8 +403,9 @@ + @@ -410,8 +420,9 @@ + @@ -427,6 +438,22 @@ xyz="0 0 0" /> + + + + + diff --git a/clearpath_manipulators_description/urdf/arm/robot.urdf b/clearpath_manipulators_description/urdf/arm/robot.urdf new file mode 100644 index 00000000..a9425465 --- /dev/null +++ b/clearpath_manipulators_description/urdf/arm/robot.urdf @@ -0,0 +1,766 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1.0 + 1.0 + 113 + 0.1651 + + + 1.0 + 1.0 + 113 + 0.1651 + + + 1.0 + 1.0 + 113 + 0.1651 + + + 1.0 + 1.0 + 113 + 0.1651 + + + + + + + + + + + + + + + + + + + + + + + + + + + clearpath_platform/A200Hardware + 0.3302 + 5.0 + 1.0 + 0.1 + /dev/clearpath/prolific + + + + -1 + 1 + + + + + + + -1 + 1 + + + + + + + -1 + 1 + + + + + + + -1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ign_ros2_control/IgnitionSystem + + + + {-2*pi} + {2*pi} + + + -3.15 + 3.15 + + + 0.0 + + + + + + + -2.41 + 2.41 + + + -3.15 + 3.15 + + + 0.0 + + + + + + + {-2*pi} + {2*pi} + + + -3.2 + 3.2 + + + 0.0 + + + + + + + -2.66 + 2.66 + + + -3.2 + 3.2 + + + 0.0 + + + + + + + {-2*pi} + {2*pi} + + + -3.2 + 3.2 + + + 0.0 + + + + + + + -2.23 + 2.23 + + + -3.2 + 3.2 + + + 0.0 + + + + + + + {-2*pi} + {2*pi} + + + -3.2 + 3.2 + + + 0.0 + + + + + + + + ogre2 + + + + + + 1.047 + + 640 + 480 + RGB_INT8 + + + 0.1 + 5 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 +
0.5 0.5
+
+ + + 554.25469 + 554.25469 + 320.5 + 240.5 + 0 + + + 554.25469 + 554.25469 + 320.5 + 240.5 + 0 + 0 + + + + gaussian + 0 + 0.00 + + + + 0.25 + 5 + + + color_optical_frame +
+ camera_color_frame + 1 + 6 + true + wrist_mounted_camera + false +
+
+ +
diff --git a/clearpath_manipulators_description/urdf/gripper/robotiq_2f_140.urdf.xacro b/clearpath_manipulators_description/urdf/gripper/robotiq_2f_140.urdf.xacro index 8a75422a..36e4d17e 100644 --- a/clearpath_manipulators_description/urdf/gripper/robotiq_2f_140.urdf.xacro +++ b/clearpath_manipulators_description/urdf/gripper/robotiq_2f_140.urdf.xacro @@ -1,5 +1,5 @@ - + @@ -17,358 +17,20 @@ isaac_joint_commands:=/isaac_joint_commands isaac_joint_states:=/isaac_joint_states com_port:=/dev/ttyUSB0"> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - topic_based_ros2_control/TopicBasedSystem - ${isaac_joint_commands} - ${isaac_joint_states} - - - ign_ros2_control/IgnitionSystem - - - mock_components/GenericSystem - ${mock_sensor_commands} - 0.0 - - - robotiq_driver/RobotiqGripperHardwareInterface - 0.695 - ${com_port} - 1.0 - 0.5 - - - - - - - - - 0.695 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + +
diff --git a/clearpath_manipulators_description/urdf/gripper/robotiq_2f_85.urdf.xacro b/clearpath_manipulators_description/urdf/gripper/robotiq_2f_85.urdf.xacro index ee4fa2fe..2f0eb3b5 100644 --- a/clearpath_manipulators_description/urdf/gripper/robotiq_2f_85.urdf.xacro +++ b/clearpath_manipulators_description/urdf/gripper/robotiq_2f_85.urdf.xacro @@ -9,9 +9,9 @@ parent_link *origin use_fake_hardware:=$(arg use_fake_hardware) - use_controllers:=$(arg use_manipulation_controllers) + use_controllers:=true fake_sensor_commands:=false - sim_ignition:=$(arg is_sim) + sim_ignition:=true sim_gazebo:=false sim_isaac:=false isaac_joint_commands:=/isaac_joint_commands diff --git a/clearpath_mounts_description/CHANGELOG.rst b/clearpath_mounts_description/CHANGELOG.rst index a27de8c6..37a22aa8 100644 --- a/clearpath_mounts_description/CHANGELOG.rst +++ b/clearpath_mounts_description/CHANGELOG.rst @@ -2,90 +2,6 @@ Changelog for package clearpath_mounts_description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* 0.2.4 -* Changes. -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* 0.2.1 -* Changes. -* Contributors: Tony Baltovski, luis-camero - -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Contributors: Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- diff --git a/clearpath_mounts_description/package.xml b/clearpath_mounts_description/package.xml index bf301a46..95f66568 100644 --- a/clearpath_mounts_description/package.xml +++ b/clearpath_mounts_description/package.xml @@ -2,7 +2,7 @@ clearpath_mounts_description - 0.3.1 + 0.2.11 Clearpath mounts URDF descriptions Chris Iverach-Brereton diff --git a/clearpath_moveit_config/.setup_assistant b/clearpath_moveit_config/.setup_assistant new file mode 100644 index 00000000..181969b7 --- /dev/null +++ b/clearpath_moveit_config/.setup_assistant @@ -0,0 +1,25 @@ +moveit_setup_assistant_config: + urdf: + package: clearpath_manipulators_description + relative_path: urdf/arm/robot.urdf + srdf: + relative_path: config/a200-0000.srdf + package_settings: + author_name: Abed Al Rahman Al Mrad + author_email: aalmrad@kinova.ca + generated_timestamp: 1725051198 + control_xacro: + command: + - position + state: + - position + - velocity + modified_urdf: + xacros: + - control_xacro + control_xacro: + command: + - position + state: + - position + - velocity \ No newline at end of file diff --git a/clearpath_moveit_config/CMakeLists.txt b/clearpath_moveit_config/CMakeLists.txt new file mode 100644 index 00000000..1d57f6ce --- /dev/null +++ b/clearpath_moveit_config/CMakeLists.txt @@ -0,0 +1,11 @@ +cmake_minimum_required(VERSION 3.22) +project(clearpath_moveit_config) + +find_package(ament_cmake REQUIRED) + +ament_package() + +install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) +install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/clearpath_moveit_config/config/a200-0000.ros2_control.xacro b/clearpath_moveit_config/config/a200-0000.ros2_control.xacro new file mode 100644 index 00000000..1c104952 --- /dev/null +++ b/clearpath_moveit_config/config/a200-0000.ros2_control.xacro @@ -0,0 +1,63 @@ + + + + + + + + + mock_components/GenericSystem + + + + + ${initial_positions['arm_0_joint_1']} + + + + + + + ${initial_positions['arm_0_joint_2']} + + + + + + + ${initial_positions['arm_0_joint_3']} + + + + + + + ${initial_positions['arm_0_joint_4']} + + + + + + + ${initial_positions['arm_0_joint_5']} + + + + + + + ${initial_positions['arm_0_joint_6']} + + + + + + + ${initial_positions['arm_0_joint_7']} + + + + + + + diff --git a/clearpath_moveit_config/config/a200-0000.srdf b/clearpath_moveit_config/config/a200-0000.srdf new file mode 100644 index 00000000..10833a77 --- /dev/null +++ b/clearpath_moveit_config/config/a200-0000.srdf @@ -0,0 +1,70 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/clearpath_moveit_config/config/a200-0000.urdf.xacro b/clearpath_moveit_config/config/a200-0000.urdf.xacro new file mode 100644 index 00000000..bc8e3ca5 --- /dev/null +++ b/clearpath_moveit_config/config/a200-0000.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/clearpath_moveit_config/config/initial_positions.yaml b/clearpath_moveit_config/config/initial_positions.yaml new file mode 100644 index 00000000..7439ac36 --- /dev/null +++ b/clearpath_moveit_config/config/initial_positions.yaml @@ -0,0 +1,10 @@ +# Default initial positions for a200-0000's ros2_control fake system + +initial_positions: + arm_0_joint_1: 0 + arm_0_joint_2: 0 + arm_0_joint_3: 0 + arm_0_joint_4: 0 + arm_0_joint_5: 0 + arm_0_joint_6: 0 + arm_0_joint_7: 0 \ No newline at end of file diff --git a/clearpath_moveit_config/config/joint_limits.yaml b/clearpath_moveit_config/config/joint_limits.yaml new file mode 100644 index 00000000..1c37a3aa --- /dev/null +++ b/clearpath_moveit_config/config/joint_limits.yaml @@ -0,0 +1,45 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + arm_0_joint_1: + has_velocity_limits: true + max_velocity: 1.3963000000000001 + has_acceleration_limits: false + max_acceleration: 0 + arm_0_joint_2: + has_velocity_limits: true + max_velocity: 1.3963000000000001 + has_acceleration_limits: false + max_acceleration: 0 + arm_0_joint_3: + has_velocity_limits: true + max_velocity: 1.3963000000000001 + has_acceleration_limits: false + max_acceleration: 0 + arm_0_joint_4: + has_velocity_limits: true + max_velocity: 1.3963000000000001 + has_acceleration_limits: false + max_acceleration: 0 + arm_0_joint_5: + has_velocity_limits: true + max_velocity: 1.2218 + has_acceleration_limits: false + max_acceleration: 0 + arm_0_joint_6: + has_velocity_limits: true + max_velocity: 1.2218 + has_acceleration_limits: false + max_acceleration: 0 + arm_0_joint_7: + has_velocity_limits: true + max_velocity: 1.2218 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/clearpath_moveit_config/config/kinematics.yaml b/clearpath_moveit_config/config/kinematics.yaml new file mode 100644 index 00000000..3fa5ae2c --- /dev/null +++ b/clearpath_moveit_config/config/kinematics.yaml @@ -0,0 +1,4 @@ +Gen3: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.0050000000000000001 + kinematics_solver_timeout: 0.0050000000000000001 \ No newline at end of file diff --git a/clearpath_moveit_config/config/moveit.rviz b/clearpath_moveit_config/config/moveit.rviz new file mode 100644 index 00000000..99bb740f --- /dev/null +++ b/clearpath_moveit_config/config/moveit.rviz @@ -0,0 +1,51 @@ +Panels: + - Class: rviz_common/Displays + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Name: Views +Visualization Manager: + Displays: + - Class: rviz_default_plugins/Grid + Name: Grid + Value: true + - Class: moveit_rviz_plugin/MotionPlanning + Name: MotionPlanning + Planned Path: + Loop Animation: true + State Display Time: 0.05 s + Trajectory Topic: display_planned_path + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Robot: + Robot Alpha: 0.5 + Value: true + Global Options: + Fixed Frame: base_link + Tools: + - Class: rviz_default_plugins/Interact + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 2.0 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Name: Current View + Pitch: 0.5 + Target Frame: base_link + Yaw: -0.623 +Window Geometry: + Height: 975 + QMainWindow State: 000000ff00000000fd0000000100000000000002b400000375fc0200000005fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb000000100044006900730070006c006100790073010000003d00000123000000c900fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000166000001910000018800fffffffb0000000800480065006c0070000000029a0000006e0000006e00fffffffb0000000a0056006900650077007301000002fd000000b5000000a400ffffff000001f60000037500000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Width: 1200 diff --git a/clearpath_moveit_config/config/moveit_controllers.yaml b/clearpath_moveit_config/config/moveit_controllers.yaml new file mode 100644 index 00000000..c7b02ec3 --- /dev/null +++ b/clearpath_moveit_config/config/moveit_controllers.yaml @@ -0,0 +1,20 @@ +# MoveIt uses this configuration for controller management +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - arm_0_joint_trajectory_controller + + arm_0_joint_trajectory_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: True + joints: + - arm_0_joint_1 + - arm_0_joint_2 + - arm_0_joint_3 + - arm_0_joint_4 + - arm_0_joint_5 + - arm_0_joint_6 + - arm_0_joint_7 + diff --git a/clearpath_moveit_config/config/ompl_planning.yaml b/clearpath_moveit_config/config/ompl_planning.yaml new file mode 100644 index 00000000..53237f1b --- /dev/null +++ b/clearpath_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,182 @@ +###################################### NOTE ############################################# +# +# This is the Humble version of this file. On other ROS2 distributions (such as Rolling), +# you might encounter errors with MoveIt regarding the syntax of the request_adpters +# section, such as: +# +# what(): parameter 'ompl.request_adapters' has invalid type: expected [string] got [string_array] +# +# This is because on Humble, MoveIt is expecting a simple string for the request adapters, +# while some distributions expect it as an array of strings instead. If it's the case for you, +# You just need to remove the folded style block (>-) and replace it by a list of strings : +# +# request_adapters: +# - default_planner_request_adapters/AddTimeOptimalParameterization +# - default_planner_request_adapters/ResolveConstraintFrames +# - default_planner_request_adapters/FixWorkspaceBounds +# - default_planner_request_adapters/FixStartStateBounds +# - default_planner_request_adapters/FixStartStateCollision +# - default_planner_request_adapters/FixStartStatePathConstraints +# +###################################### NOTE ############################################# + +planning_plugin: ompl_interface/OMPLPlanner +request_adapters: >- + default_planner_request_adapters/AddTimeOptimalParameterization + default_planner_request_adapters/ResolveConstraintFrames + default_planner_request_adapters/FixWorkspaceBounds + default_planner_request_adapters/FixStartStateBounds + default_planner_request_adapters/FixStartStateCollision + default_planner_request_adapters/FixStartStatePathConstraints +start_state_max_bounds_error: 0.1 +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ESTkConfigDefault: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECEkConfigDefault: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECEkConfigDefault: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECEkConfigDefault: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRTkConfigDefault: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnectkConfigDefault: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstarkConfigDefault: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRTkConfigDefault: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expression. default: 0.0 set in setup() + PRMkConfigDefault: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstarkConfigDefault: + type: geometric::PRMstar + FMTkConfigDefault: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMTkConfigDefault: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDSTkConfigDefault: + type: geometric::PDST + STRIDEkConfigDefault: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRTkConfigDefault: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRTkConfigDefault: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiESTkConfigDefault: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjESTkConfigDefault: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRMkConfigDefault: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstarkConfigDefault: + type: geometric::LazyPRMstar + SPARSkConfigDefault: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwokConfigDefault: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 + TrajOptDefault: + type: geometric::TrajOpt + +Gen3: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + - TrajOptDefault diff --git a/clearpath_moveit_config/config/pilz_cartesian_limits.yaml b/clearpath_moveit_config/config/pilz_cartesian_limits.yaml new file mode 100644 index 00000000..b2997caf --- /dev/null +++ b/clearpath_moveit_config/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/clearpath_moveit_config/config/ros2_controllers.yaml b/clearpath_moveit_config/config/ros2_controllers.yaml new file mode 100644 index 00000000..969f92ad --- /dev/null +++ b/clearpath_moveit_config/config/ros2_controllers.yaml @@ -0,0 +1,27 @@ +# This config file is used by ros2_control +controller_manager: + ros__parameters: + update_rate: 100 # Hz + + arm_0_joint_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController + + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + +arm_0_joint_trajectory_controller: + ros__parameters: + joints: + - arm_0_joint_1 + - arm_0_joint_2 + - arm_0_joint_3 + - arm_0_joint_4 + - arm_0_joint_5 + - arm_0_joint_6 + - arm_0_joint_7 + command_interfaces: + - position + state_interfaces: + - position + - velocity diff --git a/clearpath_moveit_config/launch/demo.launch.py b/clearpath_moveit_config/launch/demo.launch.py new file mode 100644 index 00000000..2356342f --- /dev/null +++ b/clearpath_moveit_config/launch/demo.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_demo_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_demo_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/move_group.launch.py b/clearpath_moveit_config/launch/move_group.launch.py new file mode 100644 index 00000000..7690771b --- /dev/null +++ b/clearpath_moveit_config/launch/move_group.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_move_group_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_move_group_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/moveit_rviz.launch.py b/clearpath_moveit_config/launch/moveit_rviz.launch.py new file mode 100644 index 00000000..866d243a --- /dev/null +++ b/clearpath_moveit_config/launch/moveit_rviz.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_moveit_rviz_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_moveit_rviz_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/robot.launch.py b/clearpath_moveit_config/launch/robot.launch.py new file mode 100644 index 00000000..8cc7ac44 --- /dev/null +++ b/clearpath_moveit_config/launch/robot.launch.py @@ -0,0 +1,191 @@ +#!/usr/bin/python3 + +# Import libraries: +import os +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import LaunchConfiguration +from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler, DeclareLaunchArgument +from launch.conditions import IfCondition, UnlessCondition +from launch.event_handlers import OnProcessExit +from launch.launch_description_sources import PythonLaunchDescriptionSource +import xacro +import yaml + +# LOAD FILE: +def load_file(package_name, file_path): + package_path = get_package_share_directory(package_name) + absolute_file_path = os.path.join(package_path, file_path) + try: + with open(absolute_file_path, 'r') as file: + return file.read() + except EnvironmentError: + # parent of IOError, OSError *and* WindowsError where available. + return None +# LOAD YAML: +def load_yaml(package_name, file_path): + package_path = get_package_share_directory(package_name) + absolute_file_path = os.path.join(package_path, file_path) + try: + with open(absolute_file_path, 'r') as file: + return yaml.safe_load(file) + except EnvironmentError: + # parent of IOError, OSError *and* WindowsError where available. + return None + +# ========== **GENERATE LAUNCH DESCRIPTION** ========== # +def generate_launch_description(): + + + + # ***** CONTROLLERS ***** # + # Joint STATE BROADCASTER: + joint_state_broadcaster_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"], + ) + # Joint TRAJECTORY Controller: + joint_trajectory_controller_spawner = Node( + package="controller_manager", + executable="spawner", + arguments=["irb120_controller", "-c", "/controller_manager"], + ) + + + # *********************** MoveIt!2 *********************** # + + # Command-line argument: RVIZ file? + rviz_arg = DeclareLaunchArgument( + "rviz_file", default_value="False", description="Load RVIZ file." + ) + + # *** PLANNING CONTEXT *** # + # Robot description, URDF: + robot_description_config = xacro.process_file( + os.path.join( + get_package_share_directory("irb120_ros2_gazebo"), + "urdf", + "irb120.urdf.xacro", + ) + ) + robot_description = {"robot_description": robot_description_config.toxml()} + # Robot description, SRDF: + robot_description_semantic_config = load_file( + "irb120_ros2_moveit2", "config/irb120.srdf" + ) + robot_description_semantic = { + "robot_description_semantic": robot_description_semantic_config + } + + # Kinematics.yaml file: + kinematics_yaml = load_yaml( + "irb120_ros2_moveit2", "config/kinematics.yaml" + ) + robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml} + + # Move group: OMPL Planning. + ompl_planning_pipeline_config = { + "move_group": { + "planning_plugin": "ompl_interface/OMPLPlanner", + "request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""", + "start_state_max_bounds_error": 0.1, + } + } + ompl_planning_yaml = load_yaml( + "irb120_ros2_moveit2", "config/ompl_planning.yaml" + ) + ompl_planning_pipeline_config["move_group"].update(ompl_planning_yaml) + + # MoveIt!2 Controllers: + moveit_simple_controllers_yaml = load_yaml( + "irb120_ros2_moveit2", "config/irb120_controllers.yaml" + ) + moveit_controllers = { + "moveit_simple_controller_manager": moveit_simple_controllers_yaml, + "moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager", + } + trajectory_execution = { + "moveit_manage_controllers": False, + "trajectory_execution.allowed_execution_duration_scaling": 1.2, + "trajectory_execution.allowed_goal_duration_margin": 0.5, + "trajectory_execution.allowed_start_tolerance": 0.01, + } + planning_scene_monitor_parameters = { + "publish_planning_scene": True, + "publish_geometry_updates": True, + "publish_state_updates": True, + "publish_transforms_updates": True, + } + + # START NODE -> MOVE GROUP: + run_move_group_node = Node( + package="moveit_ros_move_group", + executable="move_group", + output="screen", + parameters=[ + robot_description, + robot_description_semantic, + kinematics_yaml, + ompl_planning_pipeline_config, + trajectory_execution, + moveit_controllers, + planning_scene_monitor_parameters, + {'use_sim_time': True}, + ], + ) + + # RVIZ: + load_RVIZfile = LaunchConfiguration("rviz_file") + rviz_base = os.path.join(get_package_share_directory("irb120_ros2_moveit2"), "launch") + rviz_full_config = os.path.join(rviz_base, "irb120_moveit2.rviz") + rviz_node_full = Node( + package="rviz2", + executable="rviz2", + name="rviz2", + output="log", + arguments=["-d", rviz_full_config], + parameters=[ + robot_description, + robot_description_semantic, + ompl_planning_pipeline_config, + kinematics_yaml, + ], + condition=UnlessCondition(load_RVIZfile), + ) + + # ***** RETURN LAUNCH DESCRIPTION ***** # + return LaunchDescription([ + gazebo, + spawn_entity, + node_robot_state_publisher, + static_tf, + RegisterEventHandler( + OnProcessExit( + target_action = spawn_entity, + on_exit = [ + joint_state_broadcaster_spawner, + ] + ) + ), + RegisterEventHandler( + OnProcessExit( + target_action = joint_state_broadcaster_spawner, + on_exit = [ + joint_trajectory_controller_spawner, + ] + ) + ), + RegisterEventHandler( + OnProcessExit( + target_action = joint_trajectory_controller_spawner, + on_exit = [ + rviz_arg, + rviz_node_full, + run_move_group_node, + ] + ) + ), + ]) + \ No newline at end of file diff --git a/clearpath_moveit_config/launch/rsp.launch.py b/clearpath_moveit_config/launch/rsp.launch.py new file mode 100644 index 00000000..c8f351cf --- /dev/null +++ b/clearpath_moveit_config/launch/rsp.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_rsp_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_rsp_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/setup_assistant.launch.py b/clearpath_moveit_config/launch/setup_assistant.launch.py new file mode 100644 index 00000000..98f4038a --- /dev/null +++ b/clearpath_moveit_config/launch/setup_assistant.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_setup_assistant_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_setup_assistant_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/spawn_controllers.launch.py b/clearpath_moveit_config/launch/spawn_controllers.launch.py new file mode 100644 index 00000000..c32fff7b --- /dev/null +++ b/clearpath_moveit_config/launch/spawn_controllers.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_spawn_controllers_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_spawn_controllers_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/static_virtual_joint_tfs.launch.py b/clearpath_moveit_config/launch/static_virtual_joint_tfs.launch.py new file mode 100644 index 00000000..81a2c305 --- /dev/null +++ b/clearpath_moveit_config/launch/static_virtual_joint_tfs.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_static_virtual_joint_tfs_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_static_virtual_joint_tfs_launch(moveit_config) diff --git a/clearpath_moveit_config/launch/test.launch.py b/clearpath_moveit_config/launch/test.launch.py new file mode 100644 index 00000000..0523d0b3 --- /dev/null +++ b/clearpath_moveit_config/launch/test.launch.py @@ -0,0 +1,21 @@ +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch_ros.actions import PushRosNamespace +from launch.launch_description_sources import PythonLaunchDescriptionSource +from ament_index_python.packages import get_package_share_directory +import os + +def generate_launch_description(): + # Define the path to your demo.launch.py file + demo_launch_file = os.path.join(get_package_share_directory('clearpath_moveit_config'), 'launch', 'demo.launch.py') + + # Wrap the demo launch in a namespace using PushRosNamespace + return LaunchDescription([ + # Apply the namespace to all nodes within the group + PushRosNamespace('a200_0000'), + + # Include the demo launch file inside the namespace + IncludeLaunchDescription( + PythonLaunchDescriptionSource(demo_launch_file), + ), + ]) diff --git a/clearpath_moveit_config/launch/warehouse_db.launch.py b/clearpath_moveit_config/launch/warehouse_db.launch.py new file mode 100644 index 00000000..3d59ccf9 --- /dev/null +++ b/clearpath_moveit_config/launch/warehouse_db.launch.py @@ -0,0 +1,7 @@ +from moveit_configs_utils import MoveItConfigsBuilder +from moveit_configs_utils.launches import generate_warehouse_db_launch + + +def generate_launch_description(): + moveit_config = MoveItConfigsBuilder("a200-0000", package_name="clearpath_moveit_config").to_moveit_configs() + return generate_warehouse_db_launch(moveit_config) diff --git a/clearpath_moveit_config/package.xml b/clearpath_moveit_config/package.xml new file mode 100644 index 00000000..092890d4 --- /dev/null +++ b/clearpath_moveit_config/package.xml @@ -0,0 +1,52 @@ + + + + clearpath_moveit_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the a200-0000 with the MoveIt Motion Planning Framework + + Abed Al Rahman Al Mrad + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit2/issues + https://github.com/ros-planning/moveit2 + + Abed Al Rahman Al Mrad + + ament_cmake + + moveit_ros_move_group + moveit_kinematics + moveit_planners + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + tf2_ros + xacro + + + + clearpath_manipulators_description + controller_manager + moveit_configs_utils + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + moveit_setup_assistant + robot_state_publisher + rviz2 + rviz_common + rviz_default_plugins + tf2_ros + warehouse_ros_mongo + xacro + + + + ament_cmake + + diff --git a/clearpath_platform/CHANGELOG.rst b/clearpath_platform/CHANGELOG.rst index b304a1eb..30449095 100644 --- a/clearpath_platform/CHANGELOG.rst +++ b/clearpath_platform/CHANGELOG.rst @@ -2,96 +2,6 @@ Changelog for package clearpath_platform ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* Add headers to Puma hardware -* Updated puma topics -* PumaHardwareInterface -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* 0.2.4 -* Changes. -* Fixed lighting lib install -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* Fixed status topic names -* 0.2.1 -* Changes. -* Added needs reset lighting pattern -* Contributors: Luis Camero, Roni Kreinin, Tony Baltovski, luis-camero - -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Contributors: Luis Camero, Roni Kreinin, Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- diff --git a/clearpath_platform/launch/platform.launch.py b/clearpath_platform/launch/platform.launch.py index d45986c9..0f725755 100644 --- a/clearpath_platform/launch/platform.launch.py +++ b/clearpath_platform/launch/platform.launch.py @@ -26,6 +26,7 @@ # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +import os from launch import LaunchDescription from launch.actions import ( DeclareLaunchArgument, @@ -46,17 +47,19 @@ def generate_launch_description(): # Packages pkg_clearpath_control = FindPackageShare('clearpath_control') pkg_clearpath_platform_description = FindPackageShare('clearpath_platform_description') + home_path = os.path.expanduser('~') # Launch Arguments arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/' + default_value=PathJoinSubstitution([ + home_path, 'clearpath']) ) arg_use_sim_time = DeclareLaunchArgument( 'use_sim_time', choices=['true', 'false'], - default_value='false', + default_value='true', description='Use simulation time' ) @@ -138,12 +141,13 @@ def generate_launch_description(): # Launch clearpath_control/teleop_joy.launch.py which is tele-operation using a # physical joystick. - IncludeLaunchDescription( - PythonLaunchDescriptionSource(launch_file_teleop_joy), - launch_arguments=[ - ('setup_path', setup_path), - ('use_sim_time', use_sim_time)] - ), + +# IncludeLaunchDescription( +# PythonLaunchDescriptionSource(launch_file_teleop_joy), +# launch_arguments=[ +# ('setup_path', setup_path), +# ('use_sim_time', use_sim_time)] +# ), ] ) diff --git a/clearpath_platform/package.xml b/clearpath_platform/package.xml index a26f820c..0ffc85f9 100644 --- a/clearpath_platform/package.xml +++ b/clearpath_platform/package.xml @@ -2,7 +2,7 @@ clearpath_platform - 0.3.1 + 0.2.11 Clearpath Platform Drivers. Mike Purvis diff --git a/clearpath_platform_description/CHANGELOG.rst b/clearpath_platform_description/CHANGELOG.rst index 104466d4..cba458b1 100644 --- a/clearpath_platform_description/CHANGELOG.rst +++ b/clearpath_platform_description/CHANGELOG.rst @@ -2,118 +2,6 @@ Changelog for package clearpath_platform_description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* Add PACS mounting locations to Dingo top plate -* Standard mesh names and height parameter for tower shoulder -* R100 attachment rework -* Add dingo top plate URDF -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* Set PumaHardware in R100 -* URDF Mecanum Updates -* Switched to puma_hardware -* DingoD 1.5 Puma Hardware -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* All Warthog attachments default to 0 -* Aligned attachment links -* Added argument to prevent platform hardware from loading -* Define inertial box xacro in the arm plate urdf to be used by other platforms -* Added argument to toggle manipulator controllers -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* switch finding meshes to use the package:// command -* 0.2.4 -* Changes. -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* 0.2.1 -* Changes. -* PACS top plate was not centred with generated frames -* Added Ridgeback attachments -* Added do150 as copy of do100 -* R100 mecanum -* Only load mecanum wheels in simulation -* Removed wheel slip plugin -* Dingo O mecanum wheels -* Fixed rocker and small covariance -* Initial Ridgeback -* Initial add do100 -* Contributors: Hilary Luo, Luis Camero, Tony Baltovski, luis-camero - -* Add PACS mounting locations to Dingo top plate -* Standard mesh names and height parameter for tower shoulder -* R100 attachment rework -* Add dingo top plate URDF -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Contributors: Hilary Luo, Luis Camero, Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- diff --git a/clearpath_platform_description/launch/description.launch.py b/clearpath_platform_description/launch/description.launch.py index 6cc95ecb..f740e586 100644 --- a/clearpath_platform_description/launch/description.launch.py +++ b/clearpath_platform_description/launch/description.launch.py @@ -1,4 +1,4 @@ - +import os from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, GroupAction from launch.substitutions import (Command, FindExecutable, @@ -16,12 +16,15 @@ def generate_launch_description(): use_fake_hardware = LaunchConfiguration('use_fake_hardware') use_manipulation_controllers = LaunchConfiguration('use_manipulation_controllers') use_platform_controllers = LaunchConfiguration('use_platform_controllers') + home_path = os.path.expanduser('~') # Launch Arguments arg_setup_path = DeclareLaunchArgument( 'setup_path', - default_value='/etc/clearpath/' + default_value=PathJoinSubstitution([ + home_path, 'clearpath']) ) + arg_namespace = DeclareLaunchArgument( 'namespace', @@ -37,7 +40,7 @@ def generate_launch_description(): arg_use_manipulation_controllers = DeclareLaunchArgument( 'use_manipulation_controllers', - default_value='false', + default_value='true', description='Use manipulation controllers if true' ) @@ -62,7 +65,7 @@ def generate_launch_description(): robot_urdf, ' ', 'is_sim:=', - use_sim_time, + 'true', ' ', 'gazebo_controllers:=', config_control, @@ -74,7 +77,7 @@ def generate_launch_description(): use_fake_hardware, ' ', 'use_manipulation_controllers:=', - use_manipulation_controllers, + 'true', ' ', 'use_platform_controllers:=', use_platform_controllers, @@ -84,7 +87,7 @@ def generate_launch_description(): arg_use_sim_time = DeclareLaunchArgument( 'use_sim_time', choices=['true', 'false'], - default_value='false', + default_value='true', description='Use simulation time' ) diff --git a/clearpath_platform_description/meshes/dd100/attachments/pacs_top_plate.stl b/clearpath_platform_description/meshes/dd100/attachments/pacs_top_plate.stl deleted file mode 100644 index a391a788..00000000 Binary files a/clearpath_platform_description/meshes/dd100/attachments/pacs_top_plate.stl and /dev/null differ diff --git a/clearpath_platform_description/meshes/r100/attachments/tower_body.stl b/clearpath_platform_description/meshes/r100/attachments/dual_arm_tower_body.stl similarity index 100% rename from clearpath_platform_description/meshes/r100/attachments/tower_body.stl rename to clearpath_platform_description/meshes/r100/attachments/dual_arm_tower_body.stl diff --git a/clearpath_platform_description/meshes/r100/attachments/tower_shoulder.stl b/clearpath_platform_description/meshes/r100/attachments/dual_arm_tower_shoulder.stl similarity index 100% rename from clearpath_platform_description/meshes/r100/attachments/tower_shoulder.stl rename to clearpath_platform_description/meshes/r100/attachments/dual_arm_tower_shoulder.stl diff --git a/clearpath_platform_description/meshes/r100/attachments/fams-table-leg.stl b/clearpath_platform_description/meshes/r100/attachments/fams-table-leg.stl new file mode 100644 index 00000000..0adef87e Binary files /dev/null and b/clearpath_platform_description/meshes/r100/attachments/fams-table-leg.stl differ diff --git a/clearpath_platform_description/meshes/r100/attachments/hams_mount.stl b/clearpath_platform_description/meshes/r100/attachments/hams-arm-mount.stl similarity index 100% rename from clearpath_platform_description/meshes/r100/attachments/hams_mount.stl rename to clearpath_platform_description/meshes/r100/attachments/hams-arm-mount.stl diff --git a/clearpath_platform_description/meshes/r100/attachments/hams-table-legs.stl b/clearpath_platform_description/meshes/r100/attachments/hams-table-legs.stl new file mode 100644 index 00000000..d1deb055 Binary files /dev/null and b/clearpath_platform_description/meshes/r100/attachments/hams-table-legs.stl differ diff --git a/clearpath_platform_description/meshes/r100/attachments/hams_top.stl b/clearpath_platform_description/meshes/r100/attachments/hams-table-top.stl similarity index 100% rename from clearpath_platform_description/meshes/r100/attachments/hams_top.stl rename to clearpath_platform_description/meshes/r100/attachments/hams-table-top.stl diff --git a/clearpath_platform_description/meshes/r100/attachments/leg.stl b/clearpath_platform_description/meshes/r100/attachments/leg.stl deleted file mode 100644 index 57e22283..00000000 Binary files a/clearpath_platform_description/meshes/r100/attachments/leg.stl and /dev/null differ diff --git a/clearpath_platform_description/meshes/r100/attachments/tower_body_collision.stl b/clearpath_platform_description/meshes/r100/attachments/tower_body_collision.stl deleted file mode 100644 index 46d26f8c..00000000 Binary files a/clearpath_platform_description/meshes/r100/attachments/tower_body_collision.stl and /dev/null differ diff --git a/clearpath_platform_description/meshes/r100/attachments/tower_shoulder_collision.stl b/clearpath_platform_description/meshes/r100/attachments/tower_shoulder_collision.stl deleted file mode 100644 index 7b68ef81..00000000 Binary files a/clearpath_platform_description/meshes/r100/attachments/tower_shoulder_collision.stl and /dev/null differ diff --git a/clearpath_platform_description/package.xml b/clearpath_platform_description/package.xml index d87db77d..68711e1b 100644 --- a/clearpath_platform_description/package.xml +++ b/clearpath_platform_description/package.xml @@ -2,7 +2,7 @@ clearpath_platform_description - 0.3.1 + 0.2.11 Clearpath Platform URDF descriptions Ryan Gariepy diff --git a/clearpath_platform_description/urdf/a200/a200.urdf.xacro b/clearpath_platform_description/urdf/a200/a200.urdf.xacro index 0d8546b0..22e3283a 100644 --- a/clearpath_platform_description/urdf/a200/a200.urdf.xacro +++ b/clearpath_platform_description/urdf/a200/a200.urdf.xacro @@ -67,6 +67,14 @@ + + + + + + + + diff --git a/clearpath_platform_description/urdf/dd100/attachments/top_plate.urdf.xacro b/clearpath_platform_description/urdf/dd100/attachments/top_plate.urdf.xacro deleted file mode 100644 index cc8ddf4a..00000000 --- a/clearpath_platform_description/urdf/dd100/attachments/top_plate.urdf.xacro +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/clearpath_platform_description/urdf/dd150/attachments/top_plate.urdf.xacro b/clearpath_platform_description/urdf/dd150/attachments/top_plate.urdf.xacro deleted file mode 100644 index 0a5f405f..00000000 --- a/clearpath_platform_description/urdf/dd150/attachments/top_plate.urdf.xacro +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/clearpath_platform_description/urdf/do100/attachments/top_plate.urdf.xacro b/clearpath_platform_description/urdf/do100/attachments/top_plate.urdf.xacro deleted file mode 100644 index 0a5f405f..00000000 --- a/clearpath_platform_description/urdf/do100/attachments/top_plate.urdf.xacro +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/clearpath_platform_description/urdf/do150/attachments/top_plate.urdf.xacro b/clearpath_platform_description/urdf/do150/attachments/top_plate.urdf.xacro deleted file mode 100644 index 0a5f405f..00000000 --- a/clearpath_platform_description/urdf/do150/attachments/top_plate.urdf.xacro +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/clearpath_platform_description/urdf/links/box.urdf.xacro b/clearpath_platform_description/urdf/links/box.urdf.xacro index d2716e86..782d1c67 100644 --- a/clearpath_platform_description/urdf/links/box.urdf.xacro +++ b/clearpath_platform_description/urdf/links/box.urdf.xacro @@ -8,6 +8,13 @@ + + + + + + + diff --git a/clearpath_platform_description/urdf/r100/attachments/arm_mount.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/arm_mount.urdf.xacro new file mode 100644 index 00000000..5b1cab7a --- /dev/null +++ b/clearpath_platform_description/urdf/r100/attachments/arm_mount.urdf.xacro @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/clearpath_platform_description/urdf/r100/attachments/arm_mount/fams.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/arm_mount/fams.urdf.xacro new file mode 100644 index 00000000..0dc6cb17 --- /dev/null +++ b/clearpath_platform_description/urdf/r100/attachments/arm_mount/fams.urdf.xacro @@ -0,0 +1,156 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/clearpath_platform_description/urdf/r100/attachments/arm_mount/hams.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/arm_mount/hams.urdf.xacro new file mode 100644 index 00000000..03649ad2 --- /dev/null +++ b/clearpath_platform_description/urdf/r100/attachments/arm_mount/hams.urdf.xacro @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/clearpath_platform_description/urdf/r100/attachments/tower.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/arm_mount/tower.urdf.xacro similarity index 74% rename from clearpath_platform_description/urdf/r100/attachments/tower.urdf.xacro rename to clearpath_platform_description/urdf/r100/attachments/arm_mount/tower.urdf.xacro index 7b204014..69612dee 100644 --- a/clearpath_platform_description/urdf/r100/attachments/tower.urdf.xacro +++ b/clearpath_platform_description/urdf/r100/attachments/arm_mount/tower.urdf.xacro @@ -1,25 +1,19 @@ - - - - - - - + - + - + @@ -36,7 +30,7 @@ - + @@ -44,7 +38,7 @@ - + @@ -52,14 +46,14 @@ - + - + @@ -69,14 +63,14 @@ - + - + @@ -85,12 +79,12 @@ - + - + diff --git a/clearpath_platform_description/urdf/r100/attachments/fams.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/fams.urdf.xacro deleted file mode 100644 index 05d9c0b7..00000000 --- a/clearpath_platform_description/urdf/r100/attachments/fams.urdf.xacro +++ /dev/null @@ -1,71 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/clearpath_platform_description/urdf/r100/attachments/hams.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/hams.urdf.xacro deleted file mode 100644 index 8c457c4b..00000000 --- a/clearpath_platform_description/urdf/r100/attachments/hams.urdf.xacro +++ /dev/null @@ -1,95 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/clearpath_platform_description/urdf/r100/attachments/legs.urdf.xacro b/clearpath_platform_description/urdf/r100/attachments/legs.urdf.xacro deleted file mode 100644 index 0d80d006..00000000 --- a/clearpath_platform_description/urdf/r100/attachments/legs.urdf.xacro +++ /dev/null @@ -1,38 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/clearpath_sensors_description/CHANGELOG.rst b/clearpath_sensors_description/CHANGELOG.rst index 227d0c03..ec1c3f50 100644 --- a/clearpath_sensors_description/CHANGELOG.rst +++ b/clearpath_sensors_description/CHANGELOG.rst @@ -2,90 +2,6 @@ Changelog for package clearpath_sensors_description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -0.3.1 (2024-09-23) ------------------- - -0.3.0 (2024-09-19) ------------------- -* Changes. -* 0.3.0 Release Candidate with Main Changes (`#81 `_) - * Added tests - * Added action to build from release and source - * Generator linting erros - * Customization linting errors - * Linting - * Fix: Remove IP address from discovery server launch so it listens on all NICs - * Changes. - * 0.2.8 - * Add sysctl config file that changes ipfrag settings to support receiving large messages - * Added Zed URDF - * Added Zed to description generator - * Modified common parameter generation to always flatten - * Changes. - * 0.2.9 - * Missing important remapping to mirror hardware topics - * Added topic to gazebo plugins - * Updated topic names to match gazebo message types - * Topics of simulated onboard sensors - * Realsense adds optical links when in simulator - * Changes. - * 0.2.10 - * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF - * Fixes styling issues - * Set spawner as super client - * Changes. - * 0.2.11 - * Removed duplicate class - * Use ROS1 covariance values - * Updated renamed macanum drive controller - * Enable gazebo friction plugin on DingoO - --------- - Co-authored-by: Hilary Luo - Co-authored-by: Tony Baltovski - Co-authored-by: Steve Macenski - Co-authored-by: robbiefish -* 0.2.8 -* Changes. -* 0.2.7 -* Changes. -* 0.2.6 -* Changes. -* 0.2.5 -* Changes. -* 0.2.4 -* Changes. -* 0.2.3 -* Changes. -* 0.2.2 -* Changes.xx -* 0.2.1 -* Changes. -* Contributors: Tony Baltovski, luis-camero - -* Added tests -* Added action to build from release and source -* Generator linting erros -* Customization linting errors -* Linting -* Fix: Remove IP address from discovery server launch so it listens on all NICs -* Add sysctl config file that changes ipfrag settings to support receiving large messages -* Added Zed URDF -* Added Zed to description generator -* Modified common parameter generation to always flatten -* Missing important remapping to mirror hardware topics -* Added topic to gazebo plugins -* Updated topic names to match gazebo message types -* Topics of simulated onboard sensors -* Realsense adds optical links when in simulator -* Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF -* Fixes styling issues -* Set spawner as super client -* Removed duplicate class -* Use ROS1 covariance values -* Updated renamed macanum drive controller -* Enable gazebo friction plugin on DingoO -* Contributors: Tony Baltovski, luis-camero - 0.2.11 (2024-08-08) ------------------- * Modifies platform param to add GQ7 IMU data to ekf_localization and adds GQ7 URDF diff --git a/clearpath_sensors_description/package.xml b/clearpath_sensors_description/package.xml index 587dfddf..bc8c4cc6 100644 --- a/clearpath_sensors_description/package.xml +++ b/clearpath_sensors_description/package.xml @@ -2,7 +2,7 @@ clearpath_sensors_description - 0.3.1 + 0.2.11 Clearpath sensors URDF descriptions Luis Camero