Skip to content

Instantly share code, notes, and snippets.

@Andrew-rw
Andrew-rw / vl53l0x_tty.ino
Last active March 3, 2020 13:52
Sketch for vl53l0x ROS range sensor
#include "Adafruit_VL53L0X.h"
/*
* Protocol description.
* Every message starts with 0xAD byte, followed by message type byte and ends with \r\n (0x0D, 0x0A)
* Message types
* 0xEF - initialization failed
* 0xE0 - initialization successful, no errors
* 0x1D - range message, followed by two bytes range measurement
* 0xEA - out of range
@Andrew-rw
Andrew-rw / vl53l0x.ino
Created December 26, 2019 14:25
VL53L0X Arduino ROS node
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>
#include "Adafruit_VL53L0X.h"
ros::NodeHandle nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range( "range_data", &range_msg);
Adafruit_VL53L0X sensor = Adafruit_VL53L0X();
VL53L0X_RangingMeasurementData_t measure;
@Andrew-rw
Andrew-rw / MotorPWM.ino
Created September 1, 2019 12:27
Sketch for 37Dx70L motor control. Without closed-loop control
/*
* Simple code for the L298N motor controller
* and Metal Gearmotor 37Dx52L mm with 64 CPR Encoder
*/
#include <L298N.h>
// motor pin definition
#define M_EN 9
#define M_IN1 8
#define M_IN2 7
@Andrew-rw
Andrew-rw / test.ino
Created February 3, 2018 15:49
Arduino test bench for VL53L0X vs HC-SR04
#include "Adafruit_VL53L0X.h"
#include "HC_SR04.h"
#define TRIG_PIN 3
#define ECHO_PIN 2
#define ECHO_INT 0
HC_SR04 sensor(TRIG_PIN, ECHO_PIN, ECHO_INT);
Adafruit_VL53L0X lox = Adafruit_VL53L0X();
@Andrew-rw
Andrew-rw / kinect_view-2.rviz
Created October 1, 2017 19:12
rviz view files
Panels:
- Class: rviz/Displays
Help Height: 129
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /LaserScan1
- /PointCloud21
@Andrew-rw
Andrew-rw / depthimage_to_laserscan.launch
Created October 1, 2017 18:56
depthimage_to_laserscan node description
<launch>
<node pkg="depthimage_to_laserscan" name="depthimage_to_laserscan" type="depthimage_to_laserscan">
<remap from="image" to="camera/depth/image_raw"/>
<remap from="scan" to="depth_scan"/>
<param name="output_frame_id" value="camera_depth_frame" />
<param name="range_min" value="0.45" />
</node>
</launch>
@Andrew-rw
Andrew-rw / vidsrv.launch
Created September 23, 2017 18:10
ROS web-video-server launc example
<launch>
<!-- This node description you can take from usb_cam-test.launch -->
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
</node>