Only released in EOL distros:  

carl_bot: carl_bringup | carl_description | carl_dynamixel | carl_interactive_manipulation | carl_phidgets | carl_teleop | carl_tools

Package Summary

ROS Support for the Phidgets Spatial 3/3/3 Devices for use with the CARL Robot

About

The carl_phidgets package provides a ROS wrapper for the PhidgetSpatial Precision 3/3/3 High Resolution or the PhidgetSpatial 3/3/3 Basic sensors, and nodes that support useful IMU functionality. This includes a Kalman filter for a base sensor and a top frame sensor to determine the orientation of the base and top frame, respectively.

precision.jpg

basic.jpg

Nodes

phidgets_imu_node

ROS wrapper that allows data to be read from an IMU.

Published Topics

imu/data_raw (sensor_msgs/Imu)
  • IMU data, including 3-axis angular velocities, linear accelerations, and covariance for both (the orientation and orientation covariance are unused).
imu/mag (geometry_msgs/Vector3Stamped)
  • 3-axis magnetic orientation vector.
imu/is_calibrated (invalid message type for MsgLink(msg/type))
  • Publishes true whenever calibration is performed on the IMU.

Services

imu/calibrate (std_srvs/Empty)
  • Calibrates or recalibrates the IMU's gyro.

Parameters

period (int, default: 8)
  • Period at which to read data, in ms (4-1000 ms).
frame_id (string, default: imu)
  • Coordinate frame of the sensor.
angular_velocity_stdev (double, default: .000349)
  • Angular velocity standard deviation (rad/s).
linear_acceleration_stdev (double, default: .002943)
  • Linear acceleration standard deviation (m/s^2).
serial_number (int, default: -1)
  • Unique sensor serial number (-1 to use any detected sensor).

orientation_filter

Kalman filter sensor fusion for CARL's base and frame IMUs, to determine orientation.

Subscribed Topics

imu_base/data_raw (sensor_msgs/Imu)
  • IMU data from the base sensor.
imu_top/data_raw (sensor_msgs/Imu)
  • IMU data from the top frame sensor.

Published Topics

frame_joint_states (sensor_msgs/JointState)
  • Joint positions for the base and top frame, used for updating the transforms of the robot.

Installation

To install the carl_bot package, you can install from source with the following commands:

  •    1 cd /(your catkin workspace)/src
       2 git clone https://github.com/WPI-RAIL/carl_bot.git
       3 cd ..
       4 catkin_make
       5 catkin_make install
    

First Time Sensor Setup

To use the Phidgets IMU as a user other than root, you need to create a udev rule. Create a file called 99-phidgets.rules, with the following line:

  • SUBSYSTEMS=="usb", ACTION=="add", ATTRS{idVendor}=="06c2", ATTRS{idProduct}=="00[3-a][0-f]", MODE="666"

Copy this file into the /etc/udev/rules.d directory. You may need to reboot your computer for this to take effect.

Startup

The two IMU's placed on CARL can be launched with the following launch file:

  • roslaunch carl_phidgets imu.launch

The orientation filter can be started with:

  • rosrun carl_phidgets orientation_filter

Individual IMUs can be started with by running the IMU node separately, and specifying the sensor's unique serial number.

  • rosrun carl_phidgets phidgets_imu_node _serial_number:=xxxxxx

Wiki: carl_phidgets (last edited 2015-01-20 20:45:54 by davidkent)