Skip to content

ros params

eatal edited this page Nov 21, 2019 · 3 revisions

ROS Parameters

The list below gives an overview of the ROS parameters used by the core FlightGoggles Simulation Framework ROS nodes.

/use_sim_time
Boolean parameter used to choose between using real time and simulation time.

/run_id
Integer parameter used to keep track of the evaluation iteration.

/uav

challenge_name
String parameter used to define the name of the challenge being run (eg. easy/medium etc.) to be used for evaluation purposes.

GateX/nominal_location
Parameter that sets the nominal location of the gate, where X is the gate ID.

GateX/perturbation_bound
Parameter used to define the absolute value of the maximum allowed perturbation in the gate, defined in x y yaw.

GateX/location
Parameter that sets the true location of the gate, where X is the gate ID. The true location is obtained by adding a random perturbation (bounded by GateX/perturbation) to the nominal gate location as defined by GateX/nominal_location.

gate_names
List parameter used to define the order in which the gates are to be traversed for a particular challenge.

gate_width
Double parameter that is used to define the tolerance in the point to plane distance which can be considered as passing through a gate.

results_location
String parameter that is used to define where to store the results.yaml file.

timeout
Double parameter that defines the maximum time allowed to complete a particular challenge.

/control_nodes

universal_teleop/joy_axes/pitch
universal_teleop/joy_axes/roll
universal_teleop/joy_axes/vertical
universal_teleop/joy_axes/yaw
These axis mapping parameters for universal_teleop command muxer (integer). Remaps joystick axis i to roll, pitch, thrust, or yaw. Each must be changed to remap control axis for unsupported controllers to the correct drone control inputs.

/uav/flightgoggles_imu

accelerometer_variance
Additive white noise variance of accelerometer measurements in m^2/s^4.

gyroscope_variance
Additive white noise variance of gyroscope measurements in rad^2/s^2.

accelerometer_biasprocess
Autocorrelation value of the accelerometer bias derivatives in m^2/s^5.

gyroscope_biasprocess
Autocorrelation value of the gyroscope bias derivatives in rad^2/s^3.

accelerometer_biasinitvar
Variance of distribution of initial accelerometer bias values in (m/s^2)^2.

gyroscope_biasinitvar
Variance of distribution of initial gyroscope bias values in (rad/s)^2.

/uav/flightgoggles_laser

rangefinder_variance
Additive white noise variance of laser rangefinder measurements in m^2.

rangefinder_max_range
The maximum range of the laser rangefinder in m.

/uav/flightgoggles_lpf

gain_p
gain_q
Angular rate second-order low-pass-filter gain. This filter is used to filter gyroscope measurements before they are used as feedback signal in the angular-rate-tracking PID controller.

/uav/flightgoggles_pid

gain_p_roll
gain_i_roll
gain_d_roll
gain_p_pitch
gain_i_pitch
gain_d_pitch
gain_p_yaw
gain_i_yaw
gain_d_yaw
Angular-rate-tracking PID controller gains.

int_bound_roll
int_bound_pitch
int_bound_yaw
Angular-rate-tracking PID controller integration bounds.

vehicle_inertia_xx
vehicle_inertia_yy
vehicle_inertia_zz
moment_arm
thrust_coefficient
torque_coefficient
Vehicle parameters as in the PID controller.

/uav/flightgoggles_ros_bridge

baseline
Stereo baseline in m

image_height
Image height in pixels (max: 768).

image_width
Image Width in pixels (max: 1024).

render_stereo
Boolean parameter used to enable stereo camera simulation.

/uav/flightgoggles_uav_dynamics

init_pose
Initial condition of the quadcopter dynamics. Defined as a vector containing position x y z (in m) in world frame and the vehicle attitude as quaternion vector i j k 1.

clockscale
When defined along with /use_sim_time, enables manual scaling of simulation time with regard to wall time. Set /use_sim_time and unset this parameter to enable automatic clock scaling, which will guarantee a nominal 60Hz camera feed regardless of system load.

ignore_collisions
Determines whether collisions will reset the simulation.

vehicle_mass
In kg.

vehicle_inertia_xx
vehicle_inertia_yy
vehicle_inertia_zz
In kg m^2.

max_prop_speed
In rad/s.

moment_arm
Moment arm from motor position to vehicle center of gravity in m. This value for both the vehicle x-axis and y-axis.

motor_time_constant
Time constant used for modeling motor dynamics as first-order lag in s.

motor_rotational_inertia
Rotational inertia of motor rotor and propeller (per motor) in kg m^2.

thrust_coefficient
Propeller thrust coefficient in N/(rad/s)^2.

torque_coefficient
Propeller torque coefficient in Nm/(rad/s)^2.

drag_coefficient
Vehicle drag coefficient in N/(m/s)^2.

aeromoment_coefficient_xx
aeromoment_coefficient_yy
aeromoment_coefficient_zz
Aerodynamic moment coefficients in Nm/(rad/s)^2

moment_process_noise
Autocorrelation value of process noise applied to the vehicle as a moment in (Nm)^2 s.

force_process_noise
Autocorrelation value of process noise applied to the vehicle as a force in N^2 s.

use_ratethrust_controller
Flag to use flight controller that takes angular rates and collective thrust as inputs. The commands should be published to the topic /uav/input/rateThrust. Set this flag to false to directly command the individual motor speeds using the topic /uav/input/motorspeed.

use_rungekutta4integrator
Flat to use Runge Kutta 4th order integration. If set to false, explicit Euler integration is used.