@@ -0,0 +1 @@ | |||||
*~ |
@@ -0,0 +1,37 @@ | |||||
cmake_minimum_required(VERSION 3.8) | |||||
project(hexapod_robot) | |||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | |||||
add_compile_options(-Wall -Wextra -Wpedantic) | |||||
endif() | |||||
# find dependencies | |||||
find_package(ament_cmake REQUIRED) | |||||
# uncomment the following section in order to fill in | |||||
# further dependencies manually. | |||||
# find_package(<dependency> REQUIRED) | |||||
install( | |||||
DIRECTORY description/urdf | |||||
DESTINATION share/hexapod_robot | |||||
) | |||||
install( | |||||
DIRECTORY bringup/launch bringup/config | |||||
DESTINATION share/hexapod_robot | |||||
) | |||||
if(BUILD_TESTING) | |||||
find_package(ament_lint_auto REQUIRED) | |||||
# the following line skips the linter which checks for copyrights | |||||
# comment the line when a copyright and license is added to all source files | |||||
set(ament_cmake_copyright_FOUND TRUE) | |||||
# the following line skips cpplint (only works in a git repo) | |||||
# comment the line when this package is in a git repo and when | |||||
# a copyright and license is added to all source files | |||||
set(ament_cmake_cpplint_FOUND TRUE) | |||||
ament_lint_auto_find_test_dependencies() | |||||
endif() | |||||
ament_package() |
@@ -0,0 +1,17 @@ | |||||
Permission is hereby granted, free of charge, to any person obtaining a copy | |||||
of this software and associated documentation files (the "Software"), to deal | |||||
in the Software without restriction, including without limitation the rights | |||||
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell | |||||
copies of the Software, and to permit persons to whom the Software is | |||||
furnished to do so, subject to the following conditions: | |||||
The above copyright notice and this permission notice shall be included in | |||||
all copies or substantial portions of the Software. | |||||
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR | |||||
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, | |||||
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL | |||||
THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER | |||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, | |||||
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN | |||||
THE SOFTWARE. |
@@ -0,0 +1,327 @@ | |||||
Panels: | |||||
- Class: rviz_common/Displays | |||||
Help Height: 70 | |||||
Name: Displays | |||||
Property Tree Widget: | |||||
Expanded: | |||||
- /TF1 | |||||
Splitter Ratio: 0.5 | |||||
Tree Height: 438 | |||||
- Class: rviz_common/Views | |||||
Expanded: | |||||
- /Current View1 | |||||
Name: Views | |||||
Splitter Ratio: 0.5 | |||||
Visualization Manager: | |||||
Class: "" | |||||
Displays: | |||||
- Alpha: 0.5 | |||||
Cell Size: 1 | |||||
Class: rviz_default_plugins/Grid | |||||
Color: 160; 160; 164 | |||||
Enabled: true | |||||
Line Style: | |||||
Line Width: 0.029999999329447746 | |||||
Value: Lines | |||||
Name: Grid | |||||
Normal Cell Count: 0 | |||||
Offset: | |||||
X: 0 | |||||
Y: 0 | |||||
Z: 0 | |||||
Plane: XY | |||||
Plane Cell Count: 10 | |||||
Reference Frame: <Fixed Frame> | |||||
Value: true | |||||
- Alpha: 0.800000011920929 | |||||
Class: rviz_default_plugins/RobotModel | |||||
Collision Enabled: false | |||||
Description File: "" | |||||
Description Source: Topic | |||||
Description Topic: | |||||
Depth: 5 | |||||
Durability Policy: Volatile | |||||
History Policy: Keep Last | |||||
Reliability Policy: Reliable | |||||
Value: /robot_description | |||||
Enabled: true | |||||
Links: | |||||
All Links Enabled: true | |||||
Expand Joint Details: false | |||||
Expand Link Details: false | |||||
Expand Tree: false | |||||
Link Tree Style: Links in Alphabetic Order | |||||
base_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
c1_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
c2_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
c3_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
c4_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
c5_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
c6_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
e1_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
e2_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
e3_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
e4_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
e5_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
e6_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
f1_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
f2_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
f3_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
f4_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
f5_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
f6_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
t1_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
t2_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
t3_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
t4_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
t5_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
t6_link: | |||||
Alpha: 1 | |||||
Show Axes: false | |||||
Show Trail: false | |||||
Value: true | |||||
Mass Properties: | |||||
Inertia: false | |||||
Mass: false | |||||
Name: RobotModel | |||||
TF Prefix: "" | |||||
Update Interval: 0 | |||||
Value: true | |||||
Visual Enabled: true | |||||
- Class: rviz_default_plugins/TF | |||||
Enabled: true | |||||
Frame Timeout: 15 | |||||
Frames: | |||||
All Enabled: true | |||||
base_link: | |||||
Value: true | |||||
c1_link: | |||||
Value: true | |||||
c2_link: | |||||
Value: true | |||||
c3_link: | |||||
Value: true | |||||
c4_link: | |||||
Value: true | |||||
c5_link: | |||||
Value: true | |||||
c6_link: | |||||
Value: true | |||||
e1_link: | |||||
Value: true | |||||
e2_link: | |||||
Value: true | |||||
e3_link: | |||||
Value: true | |||||
e4_link: | |||||
Value: true | |||||
e5_link: | |||||
Value: true | |||||
e6_link: | |||||
Value: true | |||||
f1_link: | |||||
Value: true | |||||
f2_link: | |||||
Value: true | |||||
f3_link: | |||||
Value: true | |||||
f4_link: | |||||
Value: true | |||||
f5_link: | |||||
Value: true | |||||
f6_link: | |||||
Value: true | |||||
t1_link: | |||||
Value: true | |||||
t2_link: | |||||
Value: true | |||||
t3_link: | |||||
Value: true | |||||
t4_link: | |||||
Value: true | |||||
t5_link: | |||||
Value: true | |||||
t6_link: | |||||
Value: true | |||||
Marker Scale: 0.30000001192092896 | |||||
Name: TF | |||||
Show Arrows: true | |||||
Show Axes: true | |||||
Show Names: false | |||||
Tree: | |||||
base_link: | |||||
c1_link: | |||||
f1_link: | |||||
t1_link: | |||||
e1_link: | |||||
{} | |||||
c2_link: | |||||
f2_link: | |||||
t2_link: | |||||
e2_link: | |||||
{} | |||||
c3_link: | |||||
f3_link: | |||||
t3_link: | |||||
e3_link: | |||||
{} | |||||
c4_link: | |||||
f4_link: | |||||
t4_link: | |||||
e4_link: | |||||
{} | |||||
c5_link: | |||||
f5_link: | |||||
t5_link: | |||||
e5_link: | |||||
{} | |||||
c6_link: | |||||
f6_link: | |||||
t6_link: | |||||
e6_link: | |||||
{} | |||||
Update Interval: 0 | |||||
Value: true | |||||
Enabled: true | |||||
Global Options: | |||||
Background Color: 48; 48; 48 | |||||
Fixed Frame: base_link | |||||
Frame Rate: 30 | |||||
Name: root | |||||
Tools: | |||||
- Class: rviz_default_plugins/MoveCamera | |||||
Transformation: | |||||
Current: | |||||
Class: rviz_default_plugins/TF | |||||
Value: true | |||||
Views: | |||||
Current: | |||||
Class: rviz_default_plugins/Orbit | |||||
Distance: 0.8691349625587463 | |||||
Enable Stereo Rendering: | |||||
Stereo Eye Separation: 0.05999999865889549 | |||||
Stereo Focal Distance: 1 | |||||
Swap Stereo Eyes: false | |||||
Value: false | |||||
Focal Point: | |||||
X: 0 | |||||
Y: 0 | |||||
Z: 0 | |||||
Focal Shape Fixed Size: true | |||||
Focal Shape Size: 0.05000000074505806 | |||||
Invert Z Axis: false | |||||
Name: Current View | |||||
Near Clip Distance: 0.009999999776482582 | |||||
Pitch: 0.559999942779541 | |||||
Target Frame: <Fixed Frame> | |||||
Value: Orbit (rviz) | |||||
Yaw: 4.6249775886535645 | |||||
Saved: ~ | |||||
Window Geometry: | |||||
Displays: | |||||
collapsed: false | |||||
Height: 666 | |||||
Hide Left Dock: false | |||||
Hide Right Dock: false | |||||
QMainWindow State: 000000ff00000000fd0000000100000000000001560000023cfc0200000002fb000000100044006900730070006c006100790073010000003f0000023c000000cc00fffffffb0000000a0056006900650077007300000001d2000000a9000000a900ffffff000001ff0000023c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 | |||||
Views: | |||||
collapsed: false | |||||
Width: 859 | |||||
X: 0 | |||||
Y: 32 |
@@ -0,0 +1,52 @@ | |||||
from launch import LaunchDescription | |||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution | |||||
from launch_ros.actions import Node | |||||
from launch_ros.substitutions import FindPackageShare | |||||
def generate_launch_description(): | |||||
robot_description_content = Command([ | |||||
PathJoinSubstitution([FindExecutable(name="xacro")]), | |||||
" ", | |||||
PathJoinSubstitution( | |||||
[ | |||||
FindPackageShare("hexapod_robot"), | |||||
"urdf", | |||||
"hexapod_robot.urdf.xacro" | |||||
] | |||||
) | |||||
] | |||||
) | |||||
robot_description = {"robot_description": robot_description_content} | |||||
rviz_node = Node( | |||||
package="rviz2", | |||||
executable="rviz2", | |||||
arguments=['-d', PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "hexapod_robot.rviz"])], | |||||
name="rviz2", | |||||
output="screen", | |||||
) | |||||
robot_state_publisher_node = Node( | |||||
package="robot_state_publisher", | |||||
executable="robot_state_publisher", | |||||
parameters=[{ | |||||
'robot_description': robot_description_content | |||||
}] | |||||
) | |||||
joint_state_publisher_gui = Node( | |||||
package="joint_state_publisher_gui", | |||||
executable="joint_state_publisher_gui" | |||||
) | |||||
nodes = [ | |||||
rviz_node, | |||||
robot_state_publisher_node, | |||||
joint_state_publisher_gui | |||||
] | |||||
return LaunchDescription(nodes) | |||||
@@ -0,0 +1,27 @@ | |||||
<?xml version="1.0"?> | |||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hexapod_robot"> | |||||
<xacro:include filename="$(find hexapod_robot)/urdf/hexapod_robot_materials.xacro"/> | |||||
<xacro:include filename="$(find hexapod_robot)/urdf/hexapod_robot_macros.xacro"/> | |||||
<link name="base_link"> | |||||
<xacro:create_frame_plate z_offset="-0.034"/> | |||||
<xacro:create_frame_plate z_offset=" 0.034"/> | |||||
<xacro:create_coxa_joint_mount xy_offset="-0.040 0.080"/> | |||||
<xacro:create_coxa_joint_mount xy_offset="-0.060 0.000"/> | |||||
<xacro:create_coxa_joint_mount xy_offset="-0.040 -0.080"/> | |||||
<xacro:create_coxa_joint_mount xy_offset=" 0.040 -0.080"/> | |||||
<xacro:create_coxa_joint_mount xy_offset=" 0.060 0.000"/> | |||||
<xacro:create_coxa_joint_mount xy_offset=" 0.040 0.080"/> | |||||
</link> | |||||
<xacro:create_leg number="1" side="l" xy_offset="-0.040 0.080"/> | |||||
<xacro:create_leg number="2" side="l" xy_offset="-0.060 0.000"/> | |||||
<xacro:create_leg number="3" side="l" xy_offset="-0.040 -0.080"/> | |||||
<xacro:create_leg number="4" side="r" xy_offset=" 0.040 -0.080"/> | |||||
<xacro:create_leg number="5" side="r" xy_offset=" 0.060 0.000"/> | |||||
<xacro:create_leg number="6" side="r" xy_offset=" 0.040 0.080"/> | |||||
</robot> |
@@ -0,0 +1,176 @@ | |||||
<?xml version="1.0"?> | |||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hexapod_robot"> | |||||
<xacro:macro name="create_frame_plate" params="z_offset"> | |||||
<visual> | |||||
<origin xyz="0 0 ${z_offset}"/> | |||||
<geometry> | |||||
<box size="0.100 0.180 0.003"/> | |||||
</geometry> | |||||
<material name="black"/> | |||||
</visual> | |||||
</xacro:macro> | |||||
<xacro:macro name="create_coxa_joint_mount" params="xy_offset"> | |||||
<visual> | |||||
<origin xyz="${xy_offset} -0.0325"/> | |||||
<geometry> | |||||
<cylinder radius="0.0125" length="0.006"/> | |||||
</geometry> | |||||
<material name="black"/> | |||||
</visual> | |||||
<visual> | |||||
<origin xyz="${xy_offset} 0.0325"/> | |||||
<geometry> | |||||
<cylinder radius="0.0125" length="0.006"/> | |||||
</geometry> | |||||
<material name="black"/> | |||||
</visual> | |||||
</xacro:macro> | |||||
<xacro:macro name="create_coxa" params="name side xy_offset"> | |||||
<link name="${name}_link"> | |||||
<!-- coxa bounding box --> | |||||
<visual> | |||||
<geometry> | |||||
<box size="0.045 0.045 0.045"/> | |||||
</geometry> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.015 -0.005 0"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.015 -0.005 0"/></xacro:if> | |||||
<material name="blue"/> | |||||
</visual> | |||||
<!-- coxa rotation axis --> | |||||
<visual> | |||||
<geometry> | |||||
<cylinder radius="0.005" length="0.065"/> | |||||
</geometry> | |||||
<material name="blue"/> | |||||
</visual> | |||||
<!-- femur rotation axis --> | |||||
<visual> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.020 0 -0.0075" rpy="-1.57 0 0"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.020 0 -0.0075" rpy="-1.57 0 0"/></xacro:if> | |||||
<geometry> | |||||
<cylinder radius="0.005" length="0.065"/> | |||||
</geometry> | |||||
<material name="blue"/> | |||||
</visual> | |||||
</link> | |||||
<joint name="${name}_joint" type="continuous"> | |||||
<parent link="base_link"/> | |||||
<child link="${name}_link"/> | |||||
<origin xyz="${xy_offset} 0"/> | |||||
<axis xyz="0 0 1"/> | |||||
</joint> | |||||
</xacro:macro> | |||||
<xacro:macro name="create_femur" params="name parent_name side"> | |||||
<link name="${name}_link"> | |||||
<visual> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.040 0 0"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.040 0 0"/></xacro:if> | |||||
<geometry> | |||||
<box size="0.100 0.003 0.010"/> | |||||
</geometry> | |||||
<material name="green"/> | |||||
</visual> | |||||
<!-- | |||||
<visual> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.040 -0.003 0" rpy="-1.57 0 0"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.040 -0.003 0" rpy="-1.57 0 0"/></xacro:if> | |||||
<geometry> | |||||
<cylinder radius="0.0125" length="0.006"/> | |||||
</geometry> | |||||
<material name="green"/> | |||||
</visual> | |||||
--> | |||||
</link> | |||||
<joint name="${name}_joint" type="continuous"> | |||||
<parent link="${parent_name}_link"/> | |||||
<child link="${name}_link"/> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.020 0.03 -0.0075"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.020 0.03 -0.0075"/></xacro:if> | |||||
<axis xyz="0 1 0"/> | |||||
</joint> | |||||
</xacro:macro> | |||||
<xacro:macro name="create_tibia" params="name parent_name side"> | |||||
<link name="${name}_link"> | |||||
<!-- servo box --> | |||||
<visual> | |||||
<origin xyz="0 -0.005 0.010"/> | |||||
<geometry> | |||||
<box size="0.020 0.035 0.040"/> | |||||
</geometry> | |||||
<material name="red"/> | |||||
</visual> | |||||
<!-- tibia top --> | |||||
<visual> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.005 0 0.0025"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.005 0 0.0025"/></xacro:if> | |||||
<geometry> | |||||
<box size="0.040 0.003 0.075"/> | |||||
</geometry> | |||||
<material name="red"/> | |||||
</visual> | |||||
<!-- tibia middle --> | |||||
<visual> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.005 0 -0.055"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.005 0 -0.055"/></xacro:if> | |||||
<origin xyz="0 0 -0.055"/> | |||||
<geometry> | |||||
<box size="0.030 0.003 0.050"/> | |||||
</geometry> | |||||
<material name="red"/> | |||||
</visual> | |||||
<!-- tibia bottom --> | |||||
<visual> | |||||
<origin xyz=" 0.0 0 -0.105"/> | |||||
<origin xyz="0 0 -0.105"/> | |||||
<geometry> | |||||
<box size="0.010 0.003 0.050"/> | |||||
</geometry> | |||||
<material name="red"/> | |||||
</visual> | |||||
<!-- tibia rotation axis --> | |||||
<visual> | |||||
<origin xyz="0 0 0" rpy="-1.57 0 0"/> | |||||
<geometry> | |||||
<cylinder radius="0.005" length="0.065"/> | |||||
</geometry> | |||||
<material name="red"/> | |||||
</visual> | |||||
</link> | |||||
<joint name="${name}_joint" type="continuous"> | |||||
<parent link="${parent_name}_link"/> | |||||
<child link="${name}_link"/> | |||||
<xacro:if value="${side == 'l'}"><origin xyz="-0.080 -0.03 0"/></xacro:if> | |||||
<xacro:if value="${side == 'r'}"><origin xyz=" 0.080 -0.03 0"/></xacro:if> | |||||
<axis xyz="0 1 0"/> | |||||
</joint> | |||||
</xacro:macro> | |||||
<xacro:macro name="create_end" params="name side parent_name"> | |||||
<link name="${name}_link"> | |||||
<visual> | |||||
<geometry> | |||||
<sphere radius="0.004"/> | |||||
</geometry> | |||||
<material name="cyan"/> | |||||
</visual> | |||||
</link> | |||||
<joint name="${name}_joint" type="fixed"> | |||||
<parent link="${parent_name}_link"/> | |||||
<child link="${name}_link"/> | |||||
<origin xyz="0 0 -0.130"/> | |||||
</joint> | |||||
</xacro:macro> | |||||
<xacro:macro name="create_leg" params="number side xy_offset"> | |||||
<xacro:create_coxa name="c${number}" side="${side}" xy_offset="${xy_offset}"/> | |||||
<xacro:create_femur name="f${number}" side="${side}" parent_name="c${number}"/> | |||||
<xacro:create_tibia name="t${number}" side="${side}" parent_name="f${number}"/> | |||||
<xacro:create_end name="e${number}" side="${side}" parent_name="t${number}"/> | |||||
</xacro:macro> | |||||
</robot> |
@@ -0,0 +1,25 @@ | |||||
<?xml version="1.0"?> | |||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | |||||
<material name="black"> | |||||
<color rgba="0 0 0 1"/> | |||||
</material> | |||||
<material name="blue"> | |||||
<color rgba="0 0 1 1"/> | |||||
</material> | |||||
<material name="green"> | |||||
<color rgba="0 1 0 1"/> | |||||
</material> | |||||
<material name="red"> | |||||
<color rgba="1 0 0 1"/> | |||||
</material> | |||||
<material name="cyan"> | |||||
<color rgba="1 0 1 1"/> | |||||
</material> | |||||
</robot> |
@@ -0,0 +1,18 @@ | |||||
<?xml version="1.0"?> | |||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | |||||
<package format="3"> | |||||
<name>hexapod_robot</name> | |||||
<version>0.0.0</version> | |||||
<description>TODO: Package description</description> | |||||
<maintainer email="marcus@grieger.xyz">wuselfuzz</maintainer> | |||||
<license>MIT</license> | |||||
<buildtool_depend>ament_cmake</buildtool_depend> | |||||
<test_depend>ament_lint_auto</test_depend> | |||||
<test_depend>ament_lint_common</test_depend> | |||||
<export> | |||||
<build_type>ament_cmake</build_type> | |||||
</export> | |||||
</package> |