Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Add robot description #8

Draft
wants to merge 8 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 12 additions & 0 deletions src/robot_description/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
cmake_minimum_required(VERSION 3.5)
project(robot_description)

find_package(ament_cmake REQUIRED)
find_package(urdf REQUIRED)

install(
DIRECTORY launch urdf rviz
DESTINATION share/${PROJECT_NAME}
)

ament_package()
79 changes: 79 additions & 0 deletions src/robot_description/launch/description.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, Command, PathJoinSubstitution, EnvironmentVariable
from launch.conditions import IfCondition
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch_ros.parameter_descriptions import ParameterValue

def generate_launch_description():
robot_base = os.getenv('ROBOT_BASE', '2wd')

urdf_path = PathJoinSubstitution(
[FindPackageShare('robot_description'), 'urdf/robots', f"{robot_base}.urdf.xacro"]
)

rviz_config_path = PathJoinSubstitution(
[FindPackageShare('robot_description'), 'rviz', 'description.rviz']
)

return LaunchDescription([
# Arguments
DeclareLaunchArgument(
name='urdf',
default_value=urdf_path,
description='URDF path',
),

DeclareLaunchArgument(
name='publish_joints',
default_value='true',
description='Launch joint_state_publisher',
),

DeclareLaunchArgument(
name='rviz',
default_value='false',
description='Launch rviz',
),

DeclareLaunchArgument(
name="use_sim_time",
default_value="false",
description="Use simulation (Gazebo) clock if true",
),

# Nodes
Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
condition=IfCondition(LaunchConfiguration('publish_joints')),
parameters=[{
'use_sim_time': LaunchConfiguration('use_sim_time')
}],
),

Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[{
'use_sim_time': LaunchConfiguration('use_sim_time'),
'robot_description': ParameterValue(Command(['xacro ', LaunchConfiguration('urdf')]))
}],
),

Node(
package='rviz2',
executable='rviz2',
name='rviz2',
condition=IfCondition(LaunchConfiguration('rviz')),
arguments=['-d', rviz_config_path],
parameters=[{
'use_sim_time': LaunchConfiguration('use_sim_time')
}],
)
])
19 changes: 19 additions & 0 deletions src/robot_description/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?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>robot_description</name>
<version>0.0.0</version>
<description>INSA Toulouse Description Package</description>
<maintainer email="[email protected]">Ronan Bonnet</maintainer>
<license>Apache 2.0</license>
<url type="repository">https://github.com/ClubRobotInsat/Info2025</url>
<url type="bugtracker">https://github.com/ClubRobotInsat/Info2025/issues</url>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
142 changes: 142 additions & 0 deletions src/robot_description/rviz/description.rviz
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.5
Tree Height: 793
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.8999999761581421
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_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_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_footprint:
Value: true
base_link:
Value: true
Marker Scale: 0.10000000149011612
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_footprint:
base_link:
{}
Update Interval: 0
Value: true
- Class: rviz_default_plugins/Axes
Enabled: true
Length: 1
Name: Axes
Radius: 0.0010000000474974513
Reference Frame: <Fixed Frame>
Value: true
Enabled: true
Global Options:
Background Color: 238; 238; 236
Fixed Frame: base_footprint
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 0.5964717268943787
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.5003980398178101
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 6.013586521148682
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1016
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000010000000000000156000003a2fc0200000001fb000000100044006900730070006c006100790073010000003b000003a2000000c700ffffff00000624000003a200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Width: 1920
X: 0
Y: 27
25 changes: 25 additions & 0 deletions src/robot_description/urdf/2wd.properties.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="base_length" value="0.24" />
<xacro:property name="base_width" value="0.275" />
<xacro:property name="base_height" value="0.003" />
<xacro:property name="base_mass" value="1" />

<xacro:property name="wheel_radius" value="0.045" />
<xacro:property name="wheel_width" value="0.01" />
<xacro:property name="wheel_pos_x" value="0.0" />
<xacro:property name="wheel_pos_y" value="0.13" />
<xacro:property name="wheel_pos_z" value="-0.03" />
<xacro:property name="wheel_mass" value=".1" />
<xacro:property name="wheel_torque" value="20" />
<xacro:property name="front_caster_wheel" value="true" />
<xacro:property name="rear_caster_wheel" value="true" />

<xacro:property name="laser_pose">
<origin xyz="0.12 0 0.33" rpy="0 0 0"/>
</xacro:property>

<xacro:property name="depth_sensor_pose">
<origin xyz="0.14 0.0 0.045" rpy="0 0 0"/>
</xacro:property>
</robot>
40 changes: 40 additions & 0 deletions src/robot_description/urdf/inertial_macros.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >

<!-- Specify some standard inertial calculations https://en.wikipedia.org/wiki/List_of_moments_of_inertia -->
<!-- These make use of xacro's mathematical functionality -->

<xacro:macro name="inertial_sphere" params="mass radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(2/5) * mass * (radius*radius)}" ixy="0.0" ixz="0.0"
iyy="${(2/5) * mass * (radius*radius)}" iyz="0.0"
izz="${(2/5) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>


<xacro:macro name="inertial_box" params="mass x y z *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (y*y+z*z)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (x*x+z*z)}" iyz="0.0"
izz="${(1/12) * mass * (x*x+y*y)}" />
</inertial>
</xacro:macro>


<xacro:macro name="inertial_cylinder" params="mass length radius *origin">
<inertial>
<xacro:insert_block name="origin"/>
<mass value="${mass}" />
<inertia ixx="${(1/12) * mass * (3*radius*radius + length*length)}" ixy="0.0" ixz="0.0"
iyy="${(1/12) * mass * (3*radius*radius + length*length)}" iyz="0.0"
izz="${(1/2) * mass * (radius*radius)}" />
</inertial>
</xacro:macro>


</robot>
28 changes: 28 additions & 0 deletions src/robot_description/urdf/parts/base/base.gazebo.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="base_gazebo">
<gazebo reference="base_link">
<visual>
<material>
<ambient>
0.8392 0.6314 0.0 1.0
</ambient>
<diffuse>
0.8392 0.6314 0.0 1.0
</diffuse>
<specular>
0.99 0.99 0.99 1.0
</specular>
<emissive>
0.0 0.0 0.0 0.0
</emissive>
</material>
</visual>
<selfCollide>
false
</selfCollide>
<mu1 value="0.05" />
<mu2 value="0.05" />
</gazebo>
</xacro:macro>
</robot>
Loading