Skip to content

Commit

Permalink
Merge branch 'humble' of github.com:luxonis/rae-ros into imu_corr
Browse files Browse the repository at this point in the history
  • Loading branch information
Serafadam committed Mar 27, 2024
2 parents c6c7475 + d7af1d4 commit c6cb13e
Show file tree
Hide file tree
Showing 13 changed files with 220 additions and 107 deletions.
2 changes: 1 addition & 1 deletion Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ RUN apt-get update && apt-get -y install --no-install-recommends \
libsndfile1-dev \
libsndfile1

RUN pip3 install openai
RUN pip3 install openai ffmpeg-python

ENV WS=/ws
RUN mkdir -p $WS/src
Expand Down
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ This repository contains rae [ROS](https://www.ros.org/) integration files.
**Note** The RAE project is under active development so you can expect changes in the API and improvements in the performance in near future. Please report problems on Github issues as it's important for the development efforts.

- [Getting started](https://docs-beta.luxonis.com/hardware/rae/get-started/)
- [RAE SDK](https://docs-beta.luxonis.com/develop/rae/rae-sdk/)
- [RAE ROS](https://docs-beta.luxonis.com/develop/rae/rae-ros/)
- [RAE SDK](https://docs-beta.luxonis.com/hardware/rae/rae-sdk/)
- [RAE ROS](https://docs-beta.luxonis.com/hardware/rae/rae-ros/)
- [Hardware](https://docs-beta.luxonis.com/hardware/products/Rae)
- [Updating firmware](https://docs-beta.luxonis.com/hardware/rae/firmware/)
- [Updating firmware](https://docs-beta.luxonis.com/hardware/rae/firmware/)
41 changes: 32 additions & 9 deletions rae_description/urdf/rae.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
<?xml version="1.0"?>
<robot name="rae"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="sim_mode" default="false" />

<xacro:include filename="inertial_moment_calc.xacro"/>
<xacro:include filename="rae_gazebo_control.urdf.xacro"/>
<xacro:include filename="rae_ros2_control.urdf.xacro"/>
<xacro:property name="deg_to_rad" value="0.01745329251994329577" />

Expand All @@ -17,14 +18,23 @@
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</xacro:body>
</link>
<gazebo reference="base_link">
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
</sensor>
</gazebo>
<xacro:if value="$(arg sim_mode)">
<gazebo reference="rae_imu_frame">
<sensor name="rae_imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>10.0</update_rate>
<visualize>true</visualize>
<topic>rae/imu/data</topic>
<frame_id>rae_imu_frame</frame_id>
<ignition_frame_id>rae_imu_frame</ignition_frame_id>
</sensor>
</gazebo>
<gazebo>
<plugin
filename="ignition-gazebo-imu-system" name="ignition::gazebo::systems::Imu">
</plugin>
</gazebo>
</xacro:if>
<link name="base_link_back">
<xacro:body mass="0.00001" d="0.0000010" h="0.000003" w="0.00003">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0"/>
Expand Down Expand Up @@ -150,6 +160,12 @@

</visual>
</link>
<xacro:if value="$(arg sim_mode)">
<gazebo reference="left_caster_wheel">
<mu1>0.0001</mu1>
<mu2>0.0001</mu2>
</gazebo>
</xacro:if>

<joint name="base_left_caster_wheel" type="fixed">
<parent link="base_link"/>
Expand Down Expand Up @@ -184,6 +200,12 @@

</visual>
</link>
<xacro:if value="$(arg sim_mode)">
<gazebo reference="right_caster_wheel">
<mu1>0.0001</mu1>
<mu2>0.0001</mu2>
</gazebo>
</xacro:if>

<joint name="base_right_caster_wheel" type="fixed">
<parent link="base_link"/>
Expand Down Expand Up @@ -331,5 +353,6 @@
<child link="rae_imu_frame"/>
</joint>

<xacro:rae_ros2_control sim_mode="$(arg sim_mode)"/>

</robot>
20 changes: 0 additions & 20 deletions rae_description/urdf/rae_gazebo_control.urdf.xacro

This file was deleted.

123 changes: 72 additions & 51 deletions rae_description/urdf/rae_ros2_control.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,56 +1,77 @@
<?xml version="1.0"?>
<robot name="rae"
xmlns:xacro="http://ros.org/wiki/xacro">
<ros2_control name="RAE" type="system">
<hardware>
<plugin>rae_hw/RaeHW</plugin>
<param name="left_wheel_name">left_wheel_joint</param>
<param name="right_wheel_name">right_wheel_joint</param>
<param name="pwmName">/sys/class/pwm/pwmchip0</param>
<param name="pwmL">2</param>
<param name="pwmR">1</param>
<param name="phL">41</param>
<param name="phR">45</param>
<param name="enLA">42</param>
<param name="enLB">43</param>
<param name="enRA">46</param>
<param name="enRB">47</param>
<param name="encTicsPerRevL">756</param>
<param name="encTicsPerRevR">756</param>
<param name="maxVelL">32</param>
<param name="maxVelR">32</param>
<param name="closed_loopL">1</param>
<param name="PID_P_L">0.2</param>
<param name="PID_I_L">0.1</param>
<param name="PID_D_L">0.0005</param>
<param name="closed_loopR">1</param>
<param name="PID_P_R">0.2</param>
<param name="PID_I_R">0.1</param>
<param name="PID_D_R">0.0005</param>
<xacro:macro name="rae_ros2_control" params="sim_mode">
<ros2_control name="RAE" type="system">
<xacro:unless value="${sim_mode}">
<hardware>
<plugin>rae_hw/RaeHW</plugin>
<param name="left_wheel_name">left_wheel_joint</param>
<param name="right_wheel_name">right_wheel_joint</param>
<param name="pwmName">/sys/class/pwm/pwmchip0</param>
<param name="pwmL">2</param>
<param name="pwmR">1</param>
<param name="phL">41</param>
<param name="phR">45</param>
<param name="enLA">42</param>
<param name="enLB">43</param>
<param name="enRA">46</param>
<param name="enRB">47</param>
<param name="encTicsPerRevL">756</param>
<param name="encTicsPerRevR">756</param>
<param name="maxVelL">32</param>
<param name="maxVelR">32</param>
<param name="closed_loopL">1</param>
<param name="PID_P_L">0.2</param>
<param name="PID_I_L">0.1</param>
<param name="PID_D_L">0.0005</param>
<param name="closed_loopR">1</param>
<param name="PID_P_R">0.2</param>
<param name="PID_I_R">0.1</param>
<param name="PID_D_R">0.0005</param>

<param name="PID_P_IMU">5.3</param>
<param name="PID_I_IMU">4.7</param>
<param name="PID_D_IMU">0.3</param>
<param name="static_correction">0</param>

<param name="loop_rate">30</param>
<param name="chip_name">gpiochip0</param>
</hardware>
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-1.68</param>
<param name="max">1.68</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-1.68</param>
<param name="max">1.68</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>
<param name="PID_P_IMU">5.3</param>
<param name="PID_I_IMU">4.7</param>
<param name="PID_D_IMU">0.3</param>
<param name="static_correction">0</param>

<param name="loop_rate">30</param>
<param name="chip_name">gpiochip0</param>
</hardware>
</xacro:unless>
<xacro:if value="${sim_mode}">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
</xacro:if>
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-1.68</param>
<param name="max">1.68</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-1.68</param>
<param name="max">1.68</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>


<xacro:if value="${sim_mode}">
<gazebo>
<plugin filename="ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>$(find rae_hw)/config/controller.yaml</parameters>
<ros>
<remapping>/diff_controller/cmd_vel_unstamped:=/cmd_vel</remapping>
</ros>
</plugin>
</gazebo>
</xacro:if>
</xacro:macro>
</robot>
2 changes: 1 addition & 1 deletion rae_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ endif()
find_package(ament_cmake REQUIRED)

install(
DIRECTORY launch worlds
DIRECTORY config launch worlds
DESTINATION share/${PROJECT_NAME}/
)

Expand Down
39 changes: 39 additions & 0 deletions rae_gazebo/config/gz_bridge.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
- topic_name: "/clock"
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "ignition.msgs.Clock"
direction: GZ_TO_ROS

- topic_name: "/camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"
direction: GZ_TO_ROS

- topic_name: "/camera/depth_image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"
direction: GZ_TO_ROS

- topic_name: "/camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "ignition.msgs.CameraInfo"
direction: GZ_TO_ROS

- topic_name: "/image_out"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"
direction: GZ_TO_ROS

- topic_name: "/image_tuning"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "ignition.msgs.Image"
direction: GZ_TO_ROS

- topic_name: "/scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "ignition.msgs.LaserScan"
direction: GZ_TO_ROS

- topic_name: "/rae/imu/data"
ros_type_name: "sensor_msgs/msg/Imu"
gz_type_name: "ignition.msgs.IMU"
direction: GZ_TO_ROS
50 changes: 35 additions & 15 deletions rae_gazebo/launch/gazebo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,14 @@
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction, SetEnvironmentVariable
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch.conditions import IfCondition
from launch_ros.actions import Node

def launch_setup(context, *args, **kwargs):
rae_description_pkg = get_package_share_directory('rae_description')
ros_gz_sim_pkg = get_package_share_directory('ros_gz_sim')
enable_localization = LaunchConfiguration(
'enable_localization', default='true')
world_file = LaunchConfiguration('sdf_file').perform(context)
print(f'world_file: {world_file}')
return [
Expand Down Expand Up @@ -47,22 +50,10 @@ def launch_setup(context, *args, **kwargs):
Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'/cmd_vel@geometry_msgs/msg/Twist]ignition.msgs.Twist',
'/camera/image@sensor_msgs/msg/[email protected]',
'/camera/depth_image@sensor_msgs/msg/[email protected]',
'/camera/camera_info@sensor_msgs/msg/[email protected]',

'/image_out@sensor_msgs/msg/[email protected]',
'/image_tuning@sensor_msgs/msg/[email protected]',

'/odom@nav_msgs/msg/[email protected]',
'/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock',
'/tf@tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V',
'/scan@sensor_msgs/msg/[email protected]',
],
parameters=[{
'use_sim_time': True
'use_sim_time': True,
'config_file': os.path.join(get_package_share_directory(
'rae_gazebo'),'config', 'gz_bridge.yaml')
}],
output='screen'
),
Expand All @@ -75,6 +66,35 @@ def launch_setup(context, *args, **kwargs):
'-topic', 'robot_description',
],
output='screen'
),

# Activate diff controller
Node(
package='controller_manager',
namespace=LaunchConfiguration('namespace'),
executable='spawner',
arguments=['diff_controller', '-c', '/controller_manager'],
),

# Activate joint state broadcaster
Node(
package='controller_manager',
executable='spawner',
namespace=LaunchConfiguration('namespace'),
arguments=['joint_state_broadcaster',
'--controller-manager', '/controller_manager'],
),

# Activate EKF
Node(
condition=IfCondition(enable_localization),
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node',
namespace=LaunchConfiguration('namespace'),
output='screen',
parameters=[os.path.join(get_package_share_directory(
'rae_hw'), 'config', 'ekf.yaml')],
)
]

Expand Down
3 changes: 3 additions & 0 deletions rae_gazebo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,11 @@

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<depend>rae_hw</depend>
<depend>ros_gz_bridge</depend>
<depend>ros_gz_sim</depend>
<depend>ign_ros2_control</depend>
<depend>robot_localization</depend>
<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
2 changes: 1 addition & 1 deletion rae_hw/include/rae_hw/peripherals/speakers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class SpeakersNode : public rclcpp_lifecycle::LifecycleNode {

private:
void play_mp3(const char*);
void play_wav(const char*);
void play_wav(const char*, const float);
rclcpp::Service<rae_msgs::srv::PlayAudio>::SharedPtr play_audio_service_;

void play_audio_service_callback(const std::shared_ptr<rae_msgs::srv::PlayAudio::Request> request,
Expand Down
Loading

0 comments on commit c6cb13e

Please sign in to comment.