Skip to content

Commit

Permalink
Merge branch 'humble' into imu_complementary_filter
Browse files Browse the repository at this point in the history
  • Loading branch information
AnielAlexa authored Nov 6, 2023
2 parents 8a6ca81 + a4bc59a commit f8cda6d
Show file tree
Hide file tree
Showing 18 changed files with 180 additions and 75 deletions.
3 changes: 3 additions & 0 deletions .dockerignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
.git
.github
.devcontainer
23 changes: 22 additions & 1 deletion Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,33 @@ ARG BUILD_TYPE="RelWithDebInfo"

ENV DEBIAN_FRONTEND=noninteractive
RUN apt-get update \
&& apt-get -y install --no-install-recommends software-properties-common git libusb-1.0-0-dev wget zsh python3-colcon-common-extensions python3-rosdep build-essential neovim tmux htop net-tools iputils-ping gpiod gstreamer1.0-plugins-bad gstreamer1.0-alsa libasound2-dev busybox
&& apt-get -y install --no-install-recommends \
software-properties-common \
git \
nano \
libusb-1.0-0-dev \
wget \
zsh \
python3-colcon-common-extensions \
python3-rosdep \
build-essential \
neovim \
tmux \
htop \
net-tools \
iputils-ping \
gpiod \
gstreamer1.0-plugins-bad \
gstreamer1.0-alsa \
libasound2-dev \
busybox

ENV WS=/ws
RUN mkdir -p $WS/src
COPY ./ .$WS/src/rae-ros

RUN cp -R .$WS/src/rae-ros/assets/. /usr/share
RUN rm -rf .$WS/src/rae-ros/assets
RUN rm -rf .$WS/src/rae-ros/rae_gazebo

RUN cd .$WS/ && apt update && rosdep update && rosdep install --from-paths src --ignore-src -y --skip-keys depthai --skip-keys depthai_bridge --skip-keys depthai_ros_driver --skip-keys audio_msgs --skip-keys laserscan_kinect --skip-keys ira_laser_tools
Expand Down
12 changes: 9 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
# RAE ROS

This repository contains rae [ROS](https://www.ros.org/) integration files.
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.

### Setting up procedure

Expand All @@ -9,7 +10,9 @@ This repository contains rae [ROS](https://www.ros.org/) integration files.
1. Connect via USB cable or wifi `rae-<ID>`, password `wifiwifi@` (See [rae getting started documentation](https://docs.luxonis.com/projects/hardware/en/latest/pages/rae/#getting-started)).
2. To use SHH without typing password each time - `ssh-copy-id [email protected]`
3. Currently date resets after each startup to set current - ssh [email protected] sudo date -s @`( date -u +"%s" )`
4. If you want to run ROS packages while bypassing RobotHub it would be advised to stop RH agent before starting docker containers, otherwise you can easily run into conflicts as they would be competing for same hardware resources - `robothub-ctl stop`

4. If you want to run ROS packages while bypassing RobotHub it would be advised to stop RH agent before starting docker containers, otherwise you can easily run into conflicts as they would be competing for same hardware resources - `robothub-ctl stop`. **Keep in mind** that since `wpa_supplicant` is a subproccess of the RH agent, the WiFi connection will get killed along with the agent. To resolve this we recommend you manually setup the WiFi connection as done in [this guide](https://docs-beta.luxonis.com/deploy/connect-device/rae/?v=Advanced+%28manual%29).


#### Generating docker image

Expand Down Expand Up @@ -196,4 +199,7 @@ Microphone node expects audio messages and example of how to use that data (alon
audio_data = audio_data.reshape((msg.frames, msg.channels))
```

Speakers operate similarly, in that they output audio messages. In bringup package in scripts folder sound_test.py offers a decent example of how you can create audio messages. We will shortly create more demos for speakers and microphone.


Speakers operate similarly, in that they output audio messages. In bringup package in scripts folder sound_test.py offers a decent example of how you can create audio messages. We will shortly create more demos for speakers and microphone.

Binary file added assets/rae-logo-white.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
15 changes: 12 additions & 3 deletions entrypoint.sh
Original file line number Diff line number Diff line change
@@ -1,9 +1,18 @@
#!/bin/bash
set -e

# setup ros environment
echo 2 > /sys/class/pwm/pwmchip0/export && echo 1 > /sys/class/pwm/pwmchip0/export && chmod -R a+rw /sys/class/pwm/pwmchip0/pwm1/ && chmod -R a+rw /sys/class/pwm/pwmchip0/pwm2/ && chmod -R a+rw /dev/gpiochip0
# Check and export pwm channels if not already exported
for channel in 1 2; do
pwm="/sys/class/pwm/pwmchip0/pwm${channel}/"
if [ ! -d ${pwm} ]; then
echo ${channel} > /sys/class/pwm/pwmchip0/export
fi
chmod -R a+rw ${pwm}
done

chmod -R a+rw /dev/gpiochip0

source "/opt/ros/$ROS_DISTRO/setup.bash"
source "/ws/install/setup.bash"
source "$HOME/.bashrc"
exec "$@"
exec "$@"
2 changes: 1 addition & 1 deletion rae_bringup/launch/slam.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ def generate_launch_description():
DeclareLaunchArgument('sim`', default_value='False'),
DeclareLaunchArgument('use_rviz', default_value='False'),
DeclareLaunchArgument('rviz_config', default_value=rviz_config),
DeclareLaunchArgument('params_file', default_value=os.path.join(bringup_prefix, 'config', 'slam_param.yaml')),
DeclareLaunchArgument('slam_params_file', default_value=os.path.join(bringup_prefix, 'config', 'slam_param.yaml')),
]

return LaunchDescription(
Expand Down
23 changes: 14 additions & 9 deletions rae_bringup/scripts/battery_status.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
#!/usr/bin/env python3
import rclpy
import signal
import sys
from rclpy.node import Node
from rclpy.time import Time

from sensor_msgs.msg import BatteryState, Image
from std_msgs.msg import ColorRGBA
Expand Down Expand Up @@ -95,7 +96,7 @@ def listener_callback(self, msg):
led_msg = LEDControl()
led_msg.header.stamp = self.get_clock().now().to_msg()
led_msg.data = [ColorRGBA(r=0.0, g=0.0, b=0.0, a=0.0)]*40
for i in range(40):
for i in range(39):
led_msg.single_led_n = 0
led_msg.control_type = 2 # assuming 0 means "set color"

Expand All @@ -106,17 +107,21 @@ def listener_callback(self, msg):
self.publisher_led.publish(led_msg)


def signal_handler(node):
def handle(sig, frame):
if rclpy.ok():
node.destroy_node()
rclpy.shutdown()
sys.exit(0)
return handle


def main(args=None):
rclpy.init(args=args)

battery_status_node = BatteryStatusNode()

signal.signal(signal.SIGINT, signal_handler(battery_status_node))
rclpy.spin(battery_status_node)

# Destroy the node explicitly
battery_status_node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
main()
3 changes: 2 additions & 1 deletion rae_bringup/scripts/led_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@ def listener_callback(self, msg):
led_msg = LEDControl()
led_msg.header.stamp = self.get_clock().now().to_msg()
led_msg.data = [ColorRGBA(r=0.0, g=0.0, b=0.0, a=0.0)]*40
for i in range(40):

for i in range(39):
led_msg.single_led_n = 0
led_msg.control_type = 2
if i < 8:
Expand Down
9 changes: 9 additions & 0 deletions rae_camera/config/camera.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,15 @@
i_nn_config_path: /workspaces/rae_ws/src/rae-ros/rae_camera/config/yolo.json
i_disable_resize: true
i_enable_passthrough: true
imu:
i_batch_report_threshold: 5
i_max_batch_reports: 5
i_enable_rotation: true
i_message_type: IMU_WITH_MAG_SPLIT
i_sync_method: COPY
i_gyro_freq: 100
i_acc_freq: 100
i_rot_freq: 100
rgb:
i_output_isp: false
i_set_isp_scale: false
Expand Down
34 changes: 10 additions & 24 deletions rae_description/launch/rsp.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,40 +4,26 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.substitutions import Command, LaunchConfiguration
from launch_ros.actions import LoadComposableNodes, ComposableNodeContainer
from launch_ros.actions import Node
from launch_ros.descriptions import ComposableNode
from launch.conditions import IfCondition


def launch_setup(context, *args, **kwargs):
name = LaunchConfiguration('name').perform(context)
use_sim_time = LaunchConfiguration('use_sim_time')
run_container = LaunchConfiguration('run_container')
pkg_path = os.path.join(get_package_share_directory('rae_description'))
xacro_path = os.path.join(pkg_path, 'urdf', 'rae.urdf.xacro')

return [
ComposableNodeContainer(
condition=IfCondition(run_container),
name=name+"_container",
namespace="",
package="rclcpp_components",
executable="component_container",
composable_node_descriptions=[],
output="both",
),
LoadComposableNodes(
target_container=name+"_container",
composable_node_descriptions=[
ComposableNode(
package='robot_state_publisher',
plugin='robot_state_publisher::RobotStatePublisher',
name=name+'_state_publisher',
parameters=[{
'robot_description': Command(['xacro ', xacro_path, ' sim_mode:=', use_sim_time]),
'use_sim_time': use_sim_time
}]
)])
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
parameters=[{
'robot_description': Command(['xacro ', xacro_path, ' sim_mode:=', use_sim_time]),
'use_sim_time': use_sim_time
}]
)
]


Expand Down
9 changes: 8 additions & 1 deletion rae_hw/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,13 @@ install(
LIBRARY DESTINATION lib
)

add_executable(mic_node src/mic_node.cpp)
ament_target_dependencies(mic_node rclcpp audio_msgs)
target_link_libraries(mic_node ${PROJECT_NAME})

add_executable(speakers_node src/speakers_node.cpp)
ament_target_dependencies(speakers_node rclcpp audio_msgs)
target_link_libraries(speakers_node ${PROJECT_NAME})

add_executable(test_motors test/test_motors.cpp src/rae_motors.cpp)
target_link_libraries(test_motors ${GPIOD_LIBRARY})
Expand All @@ -76,7 +83,7 @@ ament_target_dependencies(test_speed rclcpp geometry_msgs)

install(TARGETS

test_motors test_encoders test_max_speed test_speed
test_motors test_encoders test_max_speed test_speed mic_node speakers_node

DESTINATION lib/${PROJECT_NAME})

Expand Down
4 changes: 4 additions & 0 deletions rae_hw/include/rae_hw/peripherals/lcd.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,13 @@
#include <linux/fb.h>
#include <sys/mman.h>
#include <sys/ioctl.h>
#include <cstring>

#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
#include "cv_bridge/cv_bridge.h"
#include "opencv2/opencv.hpp"

namespace rae_hw
{
class LCDNode : public rclcpp::Node
Expand All @@ -16,6 +18,7 @@ namespace rae_hw
~LCDNode();

void image_callback(const sensor_msgs::msg::Image::SharedPtr msg);
void display_image(const cv::Mat& img);

private:
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr subscription_;
Expand All @@ -24,5 +27,6 @@ namespace rae_hw
struct fb_var_screeninfo vinfo;
struct fb_fix_screeninfo finfo;
long screensize;
std::string default_logo_path;
};
}
2 changes: 1 addition & 1 deletion rae_hw/include/rae_hw/peripherals/led.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include "rae_msgs/msg/led_control.hpp"

#define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
#define WS2812B_NUM_LEDS 40
#define WS2812B_NUM_LEDS 39
#define WS2812B_RESET_PULSE 60
#define WS2812B_BUFFER_SIZE (WS2812B_NUM_LEDS * 24 + WS2812B_RESET_PULSE)

Expand Down
25 changes: 13 additions & 12 deletions rae_hw/launch/peripherals.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,24 +34,24 @@ def launch_setup(context, *args, **kwargs):
name='lcd_node',
package='rae_hw',
plugin='rae_hw::LCDNode',
parameters=[{
'default_logo_path': LaunchConfiguration('default_logo_path')
}],
),
ComposableNode(
name='led_node',
package='rae_hw',
plugin='rae_hw::LEDNode',
),
ComposableNode(
name='mic_node',
package='rae_hw',
plugin='rae_hw::MicNode',
),
ComposableNode(
name='motors_node',
package='rae_hw',
plugin='rae_hw::SpeakersNode',
),
)
]),

Node(
package='rae_hw',
executable='mic_node'
),
Node(
package='rae_hw',
executable='speakers_node'
),
Node(
package='rae_bringup',
executable='battery_status.py',
Expand All @@ -65,6 +65,7 @@ def generate_launch_description():
DeclareLaunchArgument('name', default_value='rae'),
DeclareLaunchArgument('run_container', default_value='true'),
DeclareLaunchArgument('enable_battery_status', default_value='true'),
DeclareLaunchArgument('default_logo_path', default_value='/usr/share/rae-logo-white.jpg'),
]

return LaunchDescription(
Expand Down
16 changes: 16 additions & 0 deletions rae_hw/src/mic_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
#include "rclcpp/rclcpp.hpp"
#include "rae_hw/peripherals/mic.hpp"

int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);

auto node = std::make_shared<rae_hw::MicNode>(rclcpp::NodeOptions());
rclcpp::executors::StaticSingleThreadedExecutor executor;
executor.add_node(node);
executor.spin();

rclcpp::shutdown();

return 0;
}
Loading

0 comments on commit f8cda6d

Please sign in to comment.