Skip to content

Commit

Permalink
uas_sensor_orientation: ident correction
Browse files Browse the repository at this point in the history
  • Loading branch information
TSC21 committed Jul 16, 2015
1 parent 9162a50 commit f895673
Showing 1 changed file with 24 additions and 24 deletions.
48 changes: 24 additions & 24 deletions mavros/src/lib/uas_sensor_orientation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,45 +35,45 @@ static const OrientationPair make_orientation(const std::string &name,
}

static const std::array<const OrientationPair, 39> sensor_orientations = {{
/* 0 */ make_orientation("NONE", 0.0, 0.0, 0.0),
/* 1 */ make_orientation("YAW_45", 0.0, 0.0, 45.0),
/* 2 */ make_orientation("YAW_90", 0.0, 0.0, 90.0),
/* 3 */ make_orientation("YAW_135", 0.0, 0.0, 135.0),
/* 4 */ make_orientation("YAW_180", 0.0, 0.0, 180.0),
/* 5 */ make_orientation("YAW_225", 0.0, 0.0, 225.0),
/* 6 */ make_orientation("YAW_270", 0.0, 0.0, 270.0),
/* 7 */ make_orientation("YAW_315", 0.0, 0.0, 315.0),
/* 8 */ make_orientation("ROLL_180", 180.0, 0.0, 0.0),
/* 0 */ make_orientation("NONE", 0.0, 0.0, 0.0),
/* 1 */ make_orientation("YAW_45", 0.0, 0.0, 45.0),
/* 2 */ make_orientation("YAW_90", 0.0, 0.0, 90.0),
/* 3 */ make_orientation("YAW_135", 0.0, 0.0, 135.0),
/* 4 */ make_orientation("YAW_180", 0.0, 0.0, 180.0),
/* 5 */ make_orientation("YAW_225", 0.0, 0.0, 225.0),
/* 6 */ make_orientation("YAW_270", 0.0, 0.0, 270.0),
/* 7 */ make_orientation("YAW_315", 0.0, 0.0, 315.0),
/* 8 */ make_orientation("ROLL_180", 180.0, 0.0, 0.0),
/* 9 */ make_orientation("ROLL_180_YAW_45", 180.0, 0.0, 45.0),
/* 10 */ make_orientation("ROLL_180_YAW_90", 180.0, 0.0, 90.0),
/* 11 */ make_orientation("ROLL_180_YAW_135", 180.0, 0.0, 135.0),
/* 12 */ make_orientation("PITCH_180", 0.0, 180.0, 0.0),
/* 12 */ make_orientation("PITCH_180", 0.0, 180.0, 0.0),
/* 13 */ make_orientation("ROLL_180_YAW_225", 180.0, 0.0, 225.0),
/* 14 */ make_orientation("ROLL_180_YAW_315", 180.0, 0.0, 270.0),
/* 15 */ make_orientation("ROLL_90", 180.0, 0.0, 315.0),
/* 16 */ make_orientation("ROLL_90_YAW_45", 90.0, 0.0, 0.0),
/* 17 */ make_orientation("ROLL_90_YAW_90", 90.0, 0.0, 45.0),
/* 14 */ make_orientation("ROLL_180_YAW_270", 180.0, 0.0, 270.0),
/* 15 */ make_orientation("ROLL_180_YAW_315", 180.0, 0.0, 315.0),
/* 16 */ make_orientation("ROLL_90", 90.0, 0.0, 0.0),
/* 17 */ make_orientation("ROLL_90_YAW_45", 90.0, 0.0, 45.0),
/* 18 */ make_orientation("ROLL_90_YAW_90", 90.0, 0.0, 90.0),
/* 19 */ make_orientation("ROLL_90_YAW_135", 90.0, 0.0, 135.0),
/* 20 */ make_orientation("ROLL_270", 270.0, 0.0, 0.0),
/* 20 */ make_orientation("ROLL_270", 270.0, 0.0, 0.0),
/* 21 */ make_orientation("ROLL_270_YAW_45", 270.0, 0.0, 45.0),
/* 22 */ make_orientation("ROLL_270_YAW_90", 270.0, 0.0, 90.0),
/* 23 */ make_orientation("ROLL_270_YAW_135", 270.0, 0.0, 135.0),
/* 24 */ make_orientation("PITCH_90", 0.0, 90.0, 0.0),
/* 25 */ make_orientation("PITCH_270", 0.0, 270.0, 0.0),
/* 24 */ make_orientation("PITCH_90", 0.0, 90.0, 0.0),
/* 25 */ make_orientation("PITCH_270", 0.0, 270.0, 0.0),
/* 26 */ make_orientation("PITCH_180_YAW_90", 0.0, 180.0, 90.0),
/* 27 */ make_orientation("PITCH_180_YAW_270", 0.0, 180.0, 270.0),
/* 27 */ make_orientation("PITCH_180_YAW_270", 0.0, 180.0, 270.0),
/* 28 */ make_orientation("ROLL_90_PITCH_90", 90.0, 90.0, 0.0),
/* 29 */ make_orientation("ROLL_180_PITCH_90", 180.0, 90.0, 0.0),
/* 30 */ make_orientation("ROLL_270_PITCH_90", 270.0, 90.0, 0.0),
/* 31 */ make_orientation("ROLL_90_PITCH_180", 90.0, 180.0, 0.0),
/* 29 */ make_orientation("ROLL_180_PITCH_90", 180.0, 90.0, 0.0),
/* 30 */ make_orientation("ROLL_270_PITCH_90", 270.0, 90.0, 0.0),
/* 31 */ make_orientation("ROLL_90_PITCH_180", 90.0, 180.0, 0.0),
/* 32 */ make_orientation("ROLL_270_PITCH_180", 270.0, 180.0, 0.0),
/* 33 */ make_orientation("ROLL_90_PITCH_270", 90.0, 270.0, 0.0),
/* 33 */ make_orientation("ROLL_90_PITCH_270", 90.0, 270.0, 0.0),
/* 34 */ make_orientation("ROLL_180_PITCH_270", 180.0, 270.0, 0.0),
/* 35 */ make_orientation("ROLL_270_PITCH_270", 270.0, 270.0, 0.0),
/* 36 */ make_orientation("ROLL_90_PITCH_180_YAW_90", 90.0, 180.0, 90.0),
/* 36 */ make_orientation("ROLL_90_PITCH_180_YAW_90", 90.0, 180.0, 90.0),
/* 37 */ make_orientation("ROLL_90_YAW_270", 90.0, 0.0, 270.0),
/* 38 */ make_orientation("ROLL_315_PITCH_315_YAW_315", 315.0, 315.0, 315.0)
/* 38 */ make_orientation("ROLL_315_PITCH_315_YAW_315", 315.0, 315.0, 315.0)
}};

std::string UAS::str_sensor_orientation(MAV_SENSOR_ORIENTATION orientation)
Expand Down

0 comments on commit f895673

Please sign in to comment.