Only released in EOL distros:  

kurt_driver: imu_recalibration | kurt_base | kurt_bringup | kurt_description | kurt_gazebo | kurt_gazebo_plugins | kurt_teleop | rotunit_snapshotter

Package Summary

This package contains a driver for KURT mobile robot bases and for their laser rotation units.

kurt_driver: imu_recalibration | kurt_base | kurt_bringup | kurt_description | kurt_gazebo | kurt_gazebo_plugins | kurt_teleop | rotunit_snapshotter

Package Summary

This package contains a driver for KURT mobile robot bases and for their laser rotation units.

kurt_driver: imu_recalibration | kurt_base | kurt_bringup | kurt_description | kurt_gazebo | rotunit_snapshotter

Package Summary

This package contains a driver for KURT mobile robot bases and for their laser rotation units.

kurt_driver: imu_recalibration | kurt_base | kurt_bringup | kurt_description | kurt_gazebo

Package Summary

Driver for KURT mobile robot bases and for their laser rotation units.

  • Maintainer: Jochen Sprickerhof <kurt-driver AT jochen.sprickerhof DOT de>
  • Author: Jochen Sprickerhof <kurt-driver AT jochen.sprickerhof DOT de>
  • License: BSD
  • Source: git https://github.com/uos/kurt_driver.git (branch: hydro_catkin)
kurt_driver: imu_recalibration | kurt_base | kurt_bringup | kurt_description | kurt_gazebo

Package Summary

Driver for KURT mobile robot bases and for their laser rotation units.

  • Maintainer: Jochen Sprickerhof <kurt-driver AT jochen.sprickerhof DOT de>
  • Author: Jochen Sprickerhof <kurt-driver AT jochen.sprickerhof DOT de>
  • License: BSD
  • Source: git https://github.com/uos/kurt_driver.git (branch: indigo_catkin)

ROS API

kurt_base

Subscribed Topics

rot_vel (geometry_msgs/Twist)
  • Commands a desired rotational velocity to the rotation unit.
cmd_vel (geometry_msgs/Twist)
  • Commands a desired velocity to the Kurt base.

Published Topics

joint_states (sensor_msgs/JointState)
  • Publishes the joint states of the wheels and the rotation unit.
odom (nav_msgs/Odometry)
  • Publishes the wheel odometry.
imu (sensor_msgs/Imu)
  • Publishes the IMU data.
range (sensor_msgs/Range)
  • Publishes ultrasound and infrared range sensor data.

Parameters

~wheel_perimeter (float, default: 0.379)
  • Wheel perimeter in m (required only for odometry; default is for kurt2_indoor).
~axis_length (float, default: 0.28)
  • Length of axis in m (required only for odometry; default is for kurt2_indoor). Axis is the one which holds the tick counters (front/back?).
~turning_adaptation (float, default: 0.69)
  • Factor that describes the portion of theoretical angular motion vs. actual angular motion. If the front and back wheels had no friction, this factor would be almost 1.0; however the lateral friction of the front and back wheels makes the middle wheels slip when the robot is turning, leading to this reduction in actual angular motion. Default is for kurt2_indoor.
~ticks_per_turn_of_wheel (int, default: 21950)
  • Number of encoder ticks per complete turn of wheel. Default is for both kurt_indoor and kurt_outdoor; kurt_fast has 5120.
~use_rotunit (bool, default: false)
  • Do we control the rotation unit?
~x_stddev (float, default: 0.002)
  • x standard deviation to be put in Odometry message
~rotation_stddev (float, default: 0.017)
  • theta standard deviation to be put in Odometry message
~cov_xy (float, default: 0.0)
  • xy covariance to be put in Odometry message
~cov_xrotation (float, default: 0.0)
  • x rotation covariance to be put in Odometry message
~cov_yrotation (float, default: 0.0)
  • y rotation covariance to be put in Odometry message
~feedforward_turn (float, default: 0.35)
  • PID parameter; unit: [m/s] (only evaluated if ~speedtable is set)
~ki (float, default: 3.4)
  • PID parameter (only evaluated if ~speedtable is set)
~kp (float, default: 0.4)
  • PID parameter (only evaluated if ~speedtable is set)
~publish_tf (bool, default: true)
  • Publish TF transform from odom to base_link?
tf_prefix (string, default: ' ')
  • The TF prefix to use
~rotunit_speed (int, default: M_PI/6.0)
  • The initial rotational speed to send to the rotation unit on startup in rad/sec.
~speedtable (string, default: required)
  • File name of speed table. If set, micro controller is disabled and software PID controller is enabled.

Wiki: kurt_base (last edited 2012-09-27 13:04:54 by JochenSprickerhof)