Skip to content

Commit

Permalink
Hooks, Cleanup and Depth Camera Transform
Browse files Browse the repository at this point in the history
  • Loading branch information
praneeth_bcr authored and ggupta9777 committed Jun 28, 2023
1 parent e70d22e commit dab7d7f
Show file tree
Hide file tree
Showing 8 changed files with 167 additions and 163 deletions.
3 changes: 0 additions & 3 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,3 @@ CATKIN_IGNORE
*.swp
log/
test/

# Unity
# Get latest from https://github.com/github/gitignore/blob/main/Unity.gitignore
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(new_bcr_robot)
find_package(ament_cmake REQUIRED)

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

ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.sh.in")
Expand Down
15 changes: 9 additions & 6 deletions hooks/new_bcr_robot.sh.in
Original file line number Diff line number Diff line change
@@ -1,9 +1,12 @@
# Default gazebo env variables
FILE=/usr/share/gazebo/setup.bash
if test -f "$FILE"; then
source $FILE
GAZEBO_CLASSIC_SOURCE_FILE=/usr/share/gazebo/setup.bash
if test -f "$GAZEBO_CLASSIC_SOURCE_FILE"; then
source $GAZEBO_CLASSIC_SOURCE_FILE
# Adding our models to the GAZEBO_MODEL_PATH
ament_prepend_unique_value GAZEBO_MODEL_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/models"
fi

# Adding our models to the GAZEBO_MODEL_PATH
ament_prepend_unique_value GAZEBO_MODEL_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/models"

GZ_FORTRESS_DIRECTORY=/usr/share/ignition
if test -d "$GZ_FORTRESS_DIRECTORY"; then
ament_prepend_unique_value IGN_GAZEBO_RESOURCE_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/models"
fi
16 changes: 15 additions & 1 deletion launch/gz.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,12 +84,26 @@ def generate_launch_description():
],
)

transform_publisher = Node(
package="tf2_ros",
executable="static_transform_publisher",
arguments = ["--x", "0.0",
"--y", "0.0",
"--z", "0.0",
"--yaw", "0.0",
"--pitch", "0.0",
"--roll", "0.0",
"--frame-id", "kinect_camera",
"--child-frame-id", "new_bcr_robot/base_link/kinect_camera"]
)

return LaunchDescription([
DeclareLaunchArgument("use_sim_time", default_value=use_sim_time),
DeclareLaunchArgument("world_file", default_value=world_file),
DeclareLaunchArgument("x", default_value="0.0"),
DeclareLaunchArgument("y", default_value="0.0"),
DeclareLaunchArgument("yaw", default_value="0.0"),
robot_state_publisher,
gz_sim, gz_spawn_entity, gz_ros2_bridge
gz_sim, gz_spawn_entity, gz_ros2_bridge,
transform_publisher
])
34 changes: 17 additions & 17 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,26 +1,26 @@
<?xml version="1.0"?>
<package format="2">
<name>new_bcr_robot</name>
<version>0.5.0</version>
<description>new_bcr_robot</description>
<name>new_bcr_robot</name>
<version>0.5.0</version>
<description>new_bcr_robot</description>

<maintainer email="[email protected]">leander</maintainer>
<maintainer email="[email protected]">leander</maintainer>

<license>(C) Black Coffee Robotics</license>
<license>(C) Black Coffee Robotics</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>ament_index_python</exec_depend>
<exec_depend>launch</exec_depend>
<exec_depend>launch_ros</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>ament_index_python</exec_depend>
<exec_depend>launch</exec_depend>
<exec_depend>launch_ros</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>xacro</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
13 changes: 4 additions & 9 deletions urdf/gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,10 @@

<gazebo>
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
<ros>
<namespace>$(arg robot_namespace)</namespace>
<remapping>cmd_vel:=cmd_vel</remapping>
<remapping>odom:=odom</remapping>
<ros>
<namespace>$(arg robot_namespace)</namespace>
<remapping>cmd_vel:=cmd_vel</remapping>
<remapping>odom:=odom</remapping>
</ros>
<legacy_mode>false</legacy_mode>
<update_rate>50.0</update_rate>
Expand All @@ -28,7 +28,6 @@
<publish_odom_tf>$(arg publish_wheel_odom_tf)</publish_odom_tf>
<publish_wheel_tf>false</publish_wheel_tf>
<publish_odom>true</publish_odom>
<!-- <odometry_source>encoder</odometry_source> -->
<max_wheel_acceleration>5.0</max_wheel_acceleration>
</plugin>
</gazebo>
Expand Down Expand Up @@ -66,7 +65,6 @@


<gazebo>

<plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
<ros>
<!-- Add namespace and remap the default topic -->
Expand Down Expand Up @@ -125,9 +123,7 @@
<!-- ........................... CAMERA PLUGIN ................................... -->

<xacro:if value="$(arg camera_enabled)">

<gazebo reference="kinect_camera">

<sensor name="kinect_camera" type="depth">
<pose> 0 0 0 0 0 0 </pose>
<visualize>true</visualize>
Expand All @@ -154,7 +150,6 @@
</plugin>
</sensor>
</gazebo>

</xacro:if>

<!--................................................................................. -->
Expand Down
169 changes: 82 additions & 87 deletions urdf/macros.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,93 +3,88 @@

<!--................................ INERTIA MATRICES .............................. -->

<xacro:macro name="cylinder_inertia" params="m r h">
<inertia ixx="${m * (3 * r * r + h * h) / 12}" ixy="0" ixz="0"
iyy="${m * (3 * r * r + h * h) / 12}" iyz="0"
izz="${m * r * r / 2}"
/>
</xacro:macro>

<xacro:macro name="box_inertia" params="m x y z">
<inertia ixx="${m * (y * y + z * z) / 12}" ixy="0" ixz="0"
iyy="${m * (x * x + z * z) / 12}" iyz="0"
izz="${m * (y * y + x * x) / 12}"
/>
</xacro:macro>

<xacro:macro name="sphere_inertia" params="m r">
<inertia ixx="${2 * m * r * r / 5}" ixy="0" ixz="0"
iyy="${2 * m * r * r / 5}" iyz="0"
izz="${2 * m * r * r / 5}"
/>
</xacro:macro>
<xacro:macro name="cylinder_inertia" params="m r h">
<inertia ixx="${m * (3 * r * r + h * h) / 12}" ixy="0" ixz="0"
iyy="${m * (3 * r * r + h * h) / 12}" iyz="0"
izz="${m * r * r / 2}"
/>
</xacro:macro>

<xacro:macro name="box_inertia" params="m x y z">
<inertia ixx="${m * (y * y + z * z) / 12}" ixy="0" ixz="0"
iyy="${m * (x * x + z * z) / 12}" iyz="0"
izz="${m * (y * y + x * x) / 12}"
/>
</xacro:macro>

<xacro:macro name="sphere_inertia" params="m r">
<inertia ixx="${2 * m * r * r / 5}" ixy="0" ixz="0"
iyy="${2 * m * r * r / 5}" iyz="0"
izz="${2 * m * r * r / 5}"
/>
</xacro:macro>

<!-- ............................... TROLLEY WHEEL DEFINITION .............................. -->

<xacro:macro name="trolley_wheel" params="cardinality dexterity origin_x origin_y origin_z">

<link name="${cardinality}_${dexterity}_wheel">
<collision>
<origin xyz="0 0 0" rpy="0 ${pi/2} ${pi/2}" />
<geometry>
<sphere radius="${trolley_wheel_radius}"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${trolley_wheel_mass}"/>
<xacro:sphere_inertia m="${trolley_wheel_mass}" r="${trolley_wheel_radius}"/>
</inertial>

<mu>0.0</mu>

</link>

<joint name="${cardinality}_${dexterity}_wheel_joint" type="fixed">
<parent link="base_link"/>
<child link="${cardinality}_${dexterity}_wheel"/>
<origin xyz="${origin_x} ${origin_y} ${origin_z}" rpy="0 0 0" />
<axis xyz="0 1 0" rpy="0 0 0" />
</joint>

<gazebo reference="${cardinality}_${dexterity}_wheel">
<material>Gazebo/Black</material>
</gazebo>

</xacro:macro>


<xacro:macro name="traction_wheel" params="cardinality dexterity origin_x origin_y origin_z">

<link name="${cardinality}_${dexterity}_wheel">
<collision>
<origin xyz="0 0 0" rpy="0 ${pi/2} ${pi/2}" />
<geometry>
<cylinder length="${traction_wheel_width}" radius="${traction_wheel_radius}"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 ${pi/2} ${pi/2}" />
<mass value="${traction_wheel_mass}"/>
<xacro:cylinder_inertia m="${traction_wheel_mass}" r="${traction_wheel_radius}" h="${traction_wheel_width}"/>
</inertial>

<mu>5.0</mu>
</link>

<joint name="${cardinality}_${dexterity}_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="${cardinality}_${dexterity}_wheel"/>
<origin xyz="${origin_x} ${origin_y} ${origin_z}" rpy="0 0 0" />
<axis xyz="0 1 0" rpy="0 0 0" />
</joint>

<gazebo reference="${cardinality}_${dexterity}_wheel">
<material>Gazebo/Black</material>
</gazebo>

</xacro:macro>

</robot>
<xacro:macro name="trolley_wheel" params="cardinality dexterity origin_x origin_y origin_z">
<link name="${cardinality}_${dexterity}_wheel">
<collision>
<origin xyz="0 0 0" rpy="0 ${pi/2} ${pi/2}" />
<geometry>
<sphere radius="${trolley_wheel_radius}"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="${trolley_wheel_mass}"/>
<xacro:sphere_inertia m="${trolley_wheel_mass}" r="${trolley_wheel_radius}"/>
</inertial>

<mu>0.0</mu>
</link>

<joint name="${cardinality}_${dexterity}_wheel_joint" type="fixed">
<parent link="base_link"/>
<child link="${cardinality}_${dexterity}_wheel"/>
<origin xyz="${origin_x} ${origin_y} ${origin_z}" rpy="0 0 0" />
<axis xyz="0 1 0" rpy="0 0 0" />
</joint>

<gazebo reference="${cardinality}_${dexterity}_wheel">
<material>Gazebo/Black</material>
</gazebo>
</xacro:macro>


<xacro:macro name="traction_wheel" params="cardinality dexterity origin_x origin_y origin_z">
<link name="${cardinality}_${dexterity}_wheel">
<collision>
<origin xyz="0 0 0" rpy="0 ${pi/2} ${pi/2}" />
<geometry>
<cylinder length="${traction_wheel_width}" radius="${traction_wheel_radius}"/>
</geometry>
</collision>

<inertial>
<origin xyz="0 0 0" rpy="0 ${pi/2} ${pi/2}" />
<mass value="${traction_wheel_mass}"/>
<xacro:cylinder_inertia m="${traction_wheel_mass}" r="${traction_wheel_radius}" h="${traction_wheel_width}"/>
</inertial>

<mu>5.0</mu>
</link>

<joint name="${cardinality}_${dexterity}_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="${cardinality}_${dexterity}_wheel"/>
<origin xyz="${origin_x} ${origin_y} ${origin_z}" rpy="0 0 0" />
<axis xyz="0 1 0" rpy="0 0 0" />
</joint>

<gazebo reference="${cardinality}_${dexterity}_wheel">
<material>Gazebo/Black</material>
</gazebo>
</xacro:macro>

</robot>
Loading

0 comments on commit dab7d7f

Please sign in to comment.