Skip to content
Open
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
3 changes: 1 addition & 2 deletions ca_description/urdf/common_properties.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,7 @@
<xacro:macro name="dummy_inertia">
<inertial>
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Call inertial_cuboid instead of creating the inertial from scratch.

<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
</inertial>
</xacro:macro>

Expand Down
2 changes: 1 addition & 1 deletion ca_description/urdf/create_2.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,5 +17,5 @@
</xacro:create_base>

<!-- Roomblock -->
<xacro:roomblock parent="base_link" visualize="$(arg visualize)"/>
<!-- <xacro:roomblock parent="base_link" visualize="$(arg visualize)"/> -->
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Check if roomblock affects how the robot moves the block. If so, check how we can mitigate this effect.

</robot>
7 changes: 6 additions & 1 deletion ca_description/urdf/create_base.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,12 @@

<xacro:create_wheel prefix="left" y_offset="${wheel_separation / 2}" wheel_radius="${wheel_radius}" wheel_width="${wheel_width}"/>
<xacro:create_wheel prefix="right" y_offset="${wheel_separation / -2}" wheel_radius="${wheel_radius}" wheel_width="${wheel_width}"/>
<xacro:caster_wheel/>
<xacro:caster_wheel name="caster_front">
<origin xyz="0.13 0 0" rpy="0 ${pi/2} ${pi/2}" />
</xacro:caster_wheel>
<xacro:caster_wheel name="caster_back">
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this new caster necessary? Check mass distributions.

<origin xyz="-0.13 0 0" rpy="0 ${pi/2} ${pi/2}" />
</xacro:caster_wheel>

<!-- Simulation sensors -->
<xacro:sim_create_base/>
Expand Down
17 changes: 4 additions & 13 deletions ca_description/urdf/create_caster_wheel.xacro
Original file line number Diff line number Diff line change
@@ -1,43 +1,34 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="caster_wheel">
<xacro:macro name="caster_wheel" params="name *origin">
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Put these changes into a new PR.


<xacro:include filename="$(find ca_description)/urdf/common_properties.xacro"/>

<xacro:property name="link_name" value="caster_wheel_link"/>
<xacro:property name="link_name" value="${name}_wheel_link"/>
<xacro:property name="parent_link" value="base_link"/>

<xacro:property name="x" value="0.13"/>
<xacro:property name="y" value="0"/>
<xacro:property name="z" value="0"/>
<xacro:property name="R" value="0"/>
<xacro:property name="P" value="${pi/2}"/>
<xacro:property name="Y" value="${pi/2}"/>

<xacro:property name="radius" value="0.018"/>

<link name="${link_name}">
<xacro:inertial_sphere mass="0.05" diameter="${2*radius}"/>

<visual>
<origin xyz="0 0 0" rpy="${R} ${P} ${Y}" />
<geometry>
<sphere radius="${radius}" />
</geometry>
</visual>

<collision>
<origin xyz="0 0 0" rpy="${R} ${P} ${Y}" />
<geometry>
<sphere radius="${radius}" />
</geometry>
</collision>
</link>

<!-- fixed because there's no transmission -->
<joint name="front_castor_joint" type="fixed">
<origin xyz="${x} ${y} ${z}" rpy="0 0 0" />
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="${parent_link}" />
<child link="${link_name}" />
<axis xyz="0 1 0" />
Expand Down
16 changes: 4 additions & 12 deletions ca_description/urdf/sensors/cliff_sensors.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -37,21 +37,13 @@
<child link="${name_front_right}_cliff_sensor_link" />
</joint>

<link name="${name_side_left}_cliff_sensor_link">
<xacro:dummy_inertia/>
</link>
<link name="${name_side_left}_cliff_sensor_link"/>
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move this into a new PR.


<link name="${name_side_right}_cliff_sensor_link">
<xacro:dummy_inertia/>
</link>
<link name="${name_side_right}_cliff_sensor_link"/>

<link name="${name_front_left}_cliff_sensor_link">
<xacro:dummy_inertia/>
</link>
<link name="${name_front_left}_cliff_sensor_link"/>

<link name="${name_front_right}_cliff_sensor_link">
<xacro:dummy_inertia/>
</link>
<link name="${name_front_right}_cliff_sensor_link"/>

<xacro:sim_create_cliff_sensors visualize="${visualize}"/>

Expand Down
4 changes: 1 addition & 3 deletions ca_description/urdf/sensors/wall_sensor.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,7 @@
<child link="wall_sensor_link" />
</joint>

<link name="wall_sensor_link">
<xacro:dummy_inertia/>
</link>
<link name="wall_sensor_link"/>
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

New PR removing inertias.


<xacro:sim_create_wall_sensor visualize="${visualize}"/>

Expand Down
15 changes: 10 additions & 5 deletions ca_gazebo/launch/create_cooperative_two_rooms.launch
Original file line number Diff line number Diff line change
@@ -1,11 +1,16 @@
<launch>
<param name="create1/amcl/initial_pose_x" value="$(optenv X1 -1)"/>
<param name="create1/amcl/initial_pose_y" value="$(optenv Y1 1)"/>
<param name="create1/amcl/initial_pose_x" value="$(optenv X1 -9.85)"/>
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should revert this change --> create a new world file with only a box.

<param name="create1/amcl/initial_pose_y" value="$(optenv Y1 1.3)"/>
<param name="create1/amcl/initial_pose_a" value="$(optenv A1 0)"/>

<param name="create2/amcl/initial_pose_x" value="$(optenv X2 1)"/>
<param name="create2/amcl/initial_pose_y" value="$(optenv Y2 1)"/>
<param name="create2/amcl/initial_pose_a" value="$(optenv A2 3.1416)"/>
<param name="create2/amcl/initial_pose_x" value="$(optenv X2 -9.85)"/>
<param name="create2/amcl/initial_pose_y" value="$(optenv Y2 -0.1)"/>
<param name="create2/amcl/initial_pose_a" value="$(optenv A2 0)"/>

<node pkg="ca_swarm" type="swarm_controller_node" name="swarm_controller_node" output="screen">
<rosparam param="swarm_robots">[create1, create2]</rosparam>
<param name="body_frame" value="unit_box"/>
</node>

<include file="$(find ca_gazebo)/launch/create_empty_world.launch">
<arg name="env" value="two_rooms"/>
Expand Down
2 changes: 1 addition & 1 deletion ca_gazebo/launch/create_empty_world.launch
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
</include>

<!-- map_server -->
<include if="$(eval str(arg('localization'))=='amcl')"
<include if="$(eval str(arg('localization')) != 'slam')"
file="$(find ca_move_base)/launch/map_server.launch">
<arg name="env" value="$(arg env)"/>
</include>
Expand Down
2 changes: 1 addition & 1 deletion ca_gazebo/launch/spawn_multirobot.launch
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

<!-- RViz -->
<include if="$(arg rviz)" file="$(find ca_tools)/launch/rviz.launch">
<arg name="config_file" value="$(find ca_tools)/rviz/multi_robot.rviz"/>
<arg name="config_file" value="$(find ca_tools)/rviz/swarm.rviz"/>
</include>
</group>

Expand Down
Loading