Only released in EOL distros:  

starmac_robots: simulated_quadrotor | starmac_robots_asctec

Package Summary

Bridge between starmac_flyer vehicle-agnostic code and the asctec_autopilot driver package

Nodes

asctec_adapter

Bridge between starmac_flyer vehicle-agnostic code and the asctec_autopilot driver package. Enables support for Ascending Technologies' Pelican MAV.

Subscribed Topics

teleop_flyer/motor_enable (std_msgs/Bool)
  • Should only be True whenever joystick trigger (deadman switch) is pressed
controller_mux/output (flyer_controller/control_mode_output)
  • The output of the currently active control mode
odom (nav_msgs/Odometry)
  • State vector
asctec_proc/imu (sensor_msgs/Imu)
  • IMU readings from asctec_autopilot
~land_now (std_msgs/Bool)
  • Set to true to initiate rapid landing
autopilot/LL_STATUS (asctec_msgs/LLStatus)
  • Low-level status message (battery voltage, etc) from asctec_autopilot

Published Topics

<based on output_topic param> (asctec_msgs/CtrlInput)
  • Control input messages for astec_autopilot
<based on estop_topic param> (std_msgs/Bool)
  • Emergency stop (motor kill) message to astec_autopilot
/diagnostics (diagnostic_msgs/DiagnosticStatus)
  • Diagnostics

Parameters

~output_topic (string, default: "autopilot/CTRL_INPUT")
  • Topic on which to publish output
~estop_topic (string, default: "autopilot/ESTOP")
  • Topic on which to publish emergency stop command
~deadman_timeout (double, default: 0.5)
  • Timeout in seconds
~alt_KP (double, default: 200.0)
  • Altitude controller proportional gain in thrust counts per meter
~alt_KI (double, default: 15.0)
  • Altitude controller integral gain in thrust counts per meter-second
~alt_KD (double, default: 300.0)
  • Altitude controller derivative gain in thrust counts per m/s
~alt_KDD (double, default: 0.0)
  • Altitude controller acceleration gain in thrust counts per m/s/s
~alt_Ilimit (double, default: 5.0)
  • Altitude controller integral term limit in thrust counts
~yaw_KP (double, default: 1.0)
  • Yaw controller proportional gain in deg/s per deg
~yaw_KI (double, default: 1.0)
  • Yaw controller integral gain in deg/s per deg-second
~yaw_KD (double, default: 0.0)
  • Yaw controller derivative gain in deg/s per deg/s
~yaw_Ilimit (double, default: 5.0)
  • Yaw controller integral term limit in deg/s
~yaw_rate_limit (double, default: 4.0)
  • Yaw controller output rate limit in deg/s
~roll_slew_rate_limit (double, default: 10.0)
  • Maximum change in output roll angle command in deg/s/s
~pitch_slew_rate_limit (double, default: 10.0)
  • Maximum change in output pitch angle command in deg/s/s
~yaw_slew_rate_limit (double, default: 5.0)
  • Maximum change in yaw angle command in deg/s/s
~nominal_thrust (int, default: 1950)
  • Thrust value at vertical equilibrium in counts (0..4095)
~thrust_mult (double, default: 1.0)
  • Factor by which output thrust will be multiplied (for testing/troubleshooting) (0..1.0)
~max_thrust (int, default: 2100)
  • Maximum thrust value that will be output in counts (0..4095)
~accel_bias (double, default: 9.81)
  • Value in m/s/s to subtract from z acceleration before using in altitude controller acceleration term
~land_now_thrust_decrease_rate (int, default: 200)
  • How fast to decrease commanded thrust in counts per second when 'land now' is commanded
~land_now_min_thrust_ratio (double, default: 0.5)
  • When 'land now' is commanded reduce thrust to this level (as fraction of ~nominal_thrust) then keep it constant
~pitch_trim (double, default: 0.0)
  • Will be added to commanded pitch (deg)
~roll_trim (double, default: 0.0)
  • Will be added to commanded roll (deg)
~yaw_offset (double, default: 0.0)
  • Angle in degrees by which to rotate (CW as viewed from above) the forward direction of the vehicle, in terms of how pitch and roll commands are interpreted. The default of zero makes 'forward' the standard direction for the Pelican, i.e. towards the rotor arm with orange tape. The normal use case for this would be when you have a forward-facing sensor (e.g. Kinect), and are flying manually and want to fly from the Kinect's point of view.

Wiki: starmac_robots_asctec (last edited 2011-02-10 19:09:21 by PatrickBouffard)