Skip to content

Commit

Permalink
Merge pull request #1 from PolySync/maint/cleanup
Browse files Browse the repository at this point in the history
Miscellaneous cleanup
  • Loading branch information
nathanaschbacher committed Jul 28, 2017
2 parents 5162dba + 7465133 commit 4d89e33
Show file tree
Hide file tree
Showing 3 changed files with 86 additions and 71 deletions.
141 changes: 78 additions & 63 deletions src/commander.c
Original file line number Diff line number Diff line change
Expand Up @@ -122,54 +122,55 @@ void commander_close( int channel )

int check_for_controller_update( )
{
unsigned int button_pressed = 0;
unsigned int disable_button = 0;

int return_code = joystick_update( );

if ( return_code == OSCC_OK )
{
return_code = get_button( JOYSTICK_BUTTON_DISABLE_CONTROLS,
&button_pressed );
&disable_button );
}

if ( return_code == OSCC_OK )
if ( return_code == OSCC_OK )
{
if ( disable_button != 0 )
{
if ( button_pressed != 0 )
{
printf( "Disabling Controls\n" );
return_code = commander_disable_controls( );
}
else
return_code = commander_disable_controls( );
}
}

unsigned int enable_button = 0;

if ( return_code == OSCC_OK )
{
return_code = get_button( JOYSTICK_BUTTON_ENABLE_CONTROLS,
&enable_button );

if ( return_code == OSCC_OK )
{
button_pressed = 0;
return_code = get_button( JOYSTICK_BUTTON_ENABLE_CONTROLS,
&button_pressed );
if ( return_code == OSCC_OK )
if ( enable_button != 0 )
{
if ( button_pressed != 0 )
{
return_code = commander_enable_controls( );
}
else
{
if ( control_enabled )
{
return_code = command_brakes( );

if ( return_code == OSCC_OK )
{
return_code = command_throttle( );
}

if ( return_code == OSCC_OK )
{
return_code = command_steering( );
}
}
}
return_code = commander_enable_controls( );
}
}
}

if ( control_enabled )
{
return_code = command_brakes( );

if ( return_code == OSCC_OK )
{
return_code = command_throttle( );
}

if ( return_code == OSCC_OK )
{
return_code = command_steering( );
}
}

return return_code;
}

Expand All @@ -190,10 +191,10 @@ static int get_normalized_position( unsigned long axis_index, double * const nor
low = -1.0;
}

( *normalized_position ) = CONSTRAIN(
((double) axis_position) / INT16_MAX,
low,
high);
( *normalized_position ) = CONSTRAIN(
((double) axis_position) / INT16_MAX,
low,
high);
}

return ( return_code );
Expand All @@ -206,26 +207,32 @@ static int check_trigger_positions( )

return_code = joystick_update( );


double normalized_brake_position = 0;

if ( return_code == OSCC_OK )
{
double normalized_brake_position = 0;
return_code = get_normalized_position( JOYSTICK_AXIS_BRAKE, &normalized_brake_position );
}

if ( return_code == OSCC_OK )
{
double normalized_throttle_position = 0;
return_code = get_normalized_position( JOYSTICK_AXIS_THROTTLE, &normalized_throttle_position );

if ( return_code == OSCC_OK )
{
if ( ( normalized_throttle_position > 0.0 ) ||
( normalized_brake_position > 0.0 ) )
{
return_code = OSCC_WARNING;
}
}
double normalized_throttle_position = 0;

if ( return_code == OSCC_OK )
{
return_code = get_normalized_position( JOYSTICK_AXIS_THROTTLE, &normalized_throttle_position );
}


if ( return_code == OSCC_OK )
{
if ( ( normalized_throttle_position > 0.0 )
|| ( normalized_brake_position > 0.0 ) )
{
return_code = OSCC_WARNING;
}
}

return return_code;
}

Expand Down Expand Up @@ -285,10 +292,12 @@ static int get_button( unsigned long button, unsigned int* const state )
( *state ) = 0;
}
}

return ( return_code );
}

// Since the OSCC API requires a normalized value, we will read in and normalzie a value from the game pad, using that as our requested brake position.
// Since the OSCC API requires a normalized value, we will read in and
// normalize a value from the game pad, using that as our requested brake position.
static int command_brakes( )
{
int return_code = OSCC_ERROR;
Expand Down Expand Up @@ -317,7 +326,9 @@ static int command_brakes( )
return ( return_code );
}

// For the throttle command, we want to send a normalized position based on the throttle position trigger. We also don't want to send throttle commands if we are currently braking.
// For the throttle command, we want to send a normalized position based on the
// throttle position trigger. We also don't want to send throttle commands if
// we are currently braking.
static int command_throttle( )
{
int return_code = OSCC_ERROR;
Expand All @@ -334,6 +345,7 @@ static int command_throttle( )
{
double normalized_brake_position = 0;

// If braking, do not throttle
return_code = get_normalized_position( JOYSTICK_AXIS_BRAKE, &normalized_brake_position );

if ( normalized_brake_position >= BRAKES_ENABLED_MIN )
Expand All @@ -358,7 +370,10 @@ static int command_throttle( )
return ( return_code );
}

// To send the steering command, we first get the normalized axis position from the game controller. Since the car will fault if it detects too much discontinuity between spoofed output signals, we use an exponential average filter to smooth our output.
// To send the steering command, we first get the normalized axis position from
// the game controller. Since the car will fault if it detects too much discontinuity
// between spoofed output signals, we use an exponential average filter to smooth
// our output.
static int command_steering( )
{
int return_code = OSCC_ERROR;
Expand Down Expand Up @@ -389,38 +404,38 @@ static int command_steering( )
}

/*
* These callback functions just check the reports for operator overrides. The
* firmware modules should have disabled themselves, but we will send the
* These callback functions just check the reports for operator overrides. The
* firmware modules should have disabled themselves, but we will send the
* command again just to be safe.
*
*/
static void throttle_callback(oscc_throttle_report_s *report)
{
if ( report->operator_override )
{
printf("Override: Throttle\n");

commander_disable_controls();

printf("Override: Throttle\n");
}
}

static void steering_callback(oscc_steering_report_s *report)
{
if ( report->operator_override )
{
printf("Override: Steering\n");

commander_disable_controls();

printf("Override: Steering\n");
}
}

static void brake_callback(oscc_brake_report_s * report)
{
if ( report->operator_override )
{
printf("Override: Brake\n");

commander_disable_controls();

printf("Override: Brake\n");
}
}

Expand All @@ -445,7 +460,7 @@ static void fault_callback(oscc_fault_report_s *report)
}

// To cast specific OBD messages, you need to know the structure of the
// data fields and the CAN_ID.
// data fields and the CAN_ID.
static void obd_callback(struct can_frame *frame)
{
if ( frame->can_id == KIA_SOUL_OBD_STEERING_WHEEL_ANGLE_CAN_ID )
Expand Down
14 changes: 7 additions & 7 deletions src/joystick.c
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ static joystick_device_data_s* joystick = NULL;

static int joystick_init_subsystem( )
{
oscc_error_t ret = OSCC_ERROR;
oscc_result_t ret = OSCC_ERROR;

if ( joystick == NULL )
{
Expand All @@ -86,7 +86,7 @@ static int joystick_init_subsystem( )

static int joystick_get_guid_at_index( unsigned long device_index )
{
oscc_error_t ret = OSCC_ERROR;
oscc_result_t ret = OSCC_ERROR;

if ( joystick != NULL )
{
Expand Down Expand Up @@ -126,7 +126,7 @@ static int joystick_get_num_devices( )

int joystick_init( )
{
oscc_error_t ret = OSCC_OK;
oscc_result_t ret = OSCC_OK;

ret = joystick_init_subsystem();

Expand Down Expand Up @@ -167,7 +167,7 @@ int joystick_init( )

int joystick_open( unsigned long device_index )
{
oscc_error_t ret = OSCC_ERROR;
oscc_result_t ret = OSCC_ERROR;

if ( joystick != NULL )
{
Expand Down Expand Up @@ -234,7 +234,7 @@ void joystick_close( )

int joystick_update( )
{
oscc_error_t ret = OSCC_ERROR;
oscc_result_t ret = OSCC_ERROR;

if ( joystick != NULL )
{
Expand All @@ -257,7 +257,7 @@ int joystick_update( )

int joystick_get_axis( unsigned long axis_index, int * const position )
{
oscc_error_t ret = OSCC_ERROR;
oscc_result_t ret = OSCC_ERROR;

if ( ( joystick != NULL ) && ( position != NULL ) )
{
Expand All @@ -276,7 +276,7 @@ int joystick_get_axis( unsigned long axis_index, int * const position )
int joystick_get_button( unsigned long button_index,
unsigned int * const button_state )
{
oscc_error_t ret = OSCC_ERROR;
oscc_result_t ret = OSCC_ERROR;

if ( ( joystick != NULL ) && ( button_state != NULL ) )
{
Expand Down
2 changes: 1 addition & 1 deletion src/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void signal_handler( int signal_number )

int main( int argc, char **argv )
{
oscc_error_t ret = OSCC_OK;
oscc_result_t ret = OSCC_OK;
unsigned long long update_timestamp = get_timestamp_micro();
unsigned long long elapsed_time = 0;

Expand Down

0 comments on commit 4d89e33

Please sign in to comment.