Skip to content

Commit

Permalink
Convert to ament_cmake_python package.
Browse files Browse the repository at this point in the history
  • Loading branch information
maxpolzin committed Feb 4, 2024
1 parent 4b51dc9 commit ddd60aa
Show file tree
Hide file tree
Showing 11 changed files with 23 additions and 42 deletions.
1 change: 1 addition & 0 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \
ros-${ROS_DISTRO}-demo-nodes-py \
ros-${ROS_DISTRO}-dynamixel-workbench-toolbox \
ros-${ROS_DISTRO}-robot-state-publisher \
ros-${ROS_DISTRO}-joint-state-publisher \
ros-${ROS_DISTRO}-xacro \
ros-${ROS_DISTRO}-ros2-controllers \
&& rm -rf /var/lib/apt/lists/*
Expand Down
1 change: 0 additions & 1 deletion helix_bringup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@ ament_python_install_package(${PROJECT_NAME} SCRIPTS_DESTINATION lib/${PROJECT_N

# Install launch and config files.
install(DIRECTORY
config
launch
DESTINATION share/${PROJECT_NAME}/
)
Expand Down
3 changes: 0 additions & 3 deletions helix_bringup/config/params.yaml

This file was deleted.

21 changes: 12 additions & 9 deletions helix_bringup/launch/helix_bringup.launch.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
import os

import xacro
from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch_ros.actions import Node

Expand All @@ -22,6 +25,7 @@ def generate_launch_description():

robot_description = os.path.join(get_package_share_directory("helix_description"), "urdf", "helix.urdf.xacro")
robot_description_config = xacro.process_file(robot_description)

robot_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
Expand All @@ -40,9 +44,12 @@ def generate_launch_description():
}]
)




controller_config = os.path.join(
get_package_share_directory(
"dynamixel_block_description"), "controllers", "controllers.yaml"
"helix_description"), "config", "controllers.yaml"
)

dynamixel_block_ros2_control_node = Node(
Expand All @@ -53,15 +60,11 @@ def generate_launch_description():
output="screen",
)

joint_publisher_config = os.path.join(
get_package_share_directory(
"helix_description"), "config", "params.yaml"
)

dynamixel_block_joint_state_broadcaster_node = Node(
package="controller_manager",
executable="spawner",
arguments=["dynamixel_joint_state_publisher", "--controller-manager", "/controller_manager", "-p", joint_publisher_config],
arguments=["dynamixel_joint_state_publisher", "--controller-manager", "/controller_manager"],
parameters=[controller_config],
output="screen",
)

Expand All @@ -75,8 +78,8 @@ def generate_launch_description():



ld.add_action(talker_node)
ld.add_action(listener_node)
# ld.add_action(talker_node)
# ld.add_action(listener_node)
ld.add_action(robot_state_publisher)
ld.add_action(joint_state_publisher_node)
ld.add_action(dynamixel_block_ros2_control_node)
Expand Down
3 changes: 3 additions & 0 deletions helix_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_python</buildtool_depend>

<exec_depend>helix_description</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
Empty file.
4 changes: 0 additions & 4 deletions helix_bringup/setup.cfg

This file was deleted.

23 changes: 0 additions & 23 deletions helix_bringup/setup.py

This file was deleted.

2 changes: 1 addition & 1 deletion helix_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ find_package(dynamixel_hardware REQUIRED)
install(DIRECTORY
meshes
urdf
controllers
config
DESTINATION share/${PROJECT_NAME}
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ controller_manager:
dynamixel_joint_state_publisher:
type: joint_state_broadcaster/JointStateBroadcaster


dynamixel_position_controller:
ros__parameters:
joints:
Expand All @@ -23,3 +24,7 @@ dynamixel_position_controller:
- dynamixel9
- dynamixel10
- dynamixel11

dynamixel_joint_state_publisher:
ros__parameters:
use_local_topics: True
2 changes: 1 addition & 1 deletion helix_description/urdf/helix.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0" ?>
<robot name="URDF_Hand" xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find helix_description)/urdf/helix_description.materials.xacro" />
<xacro:include filename="$(find helix_description)/urdf/helix.materials.xacro" />

<link name="base_link">
<inertial>
Expand Down

0 comments on commit ddd60aa

Please sign in to comment.