1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

OP-1274 Remove unneeded cast from task name in xTaskCreate call

This commit is contained in:
Alessio Morale 2014-06-18 01:47:43 +02:00
parent 07d2e27276
commit eb5deb3eca
26 changed files with 34 additions and 34 deletions

View File

@ -101,7 +101,7 @@ typedef struct {
int32_t ActuatorStart()
{
// Start main task
xTaskCreate(actuatorTask, (const char *)"Actuator", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
xTaskCreate(actuatorTask, "Actuator", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ACTUATOR, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);

View File

@ -81,7 +81,7 @@ int32_t AirspeedStart()
}
// Start main task
xTaskCreate(airspeedTask, (const char *)"Airspeed", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
xTaskCreate(airspeedTask, "Airspeed", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_AIRSPEED, taskHandle);
return 0;
}

View File

@ -68,7 +68,7 @@ static void SettingsUpdatedCb(UAVObjEvent *ev);
int32_t AltitudeStart()
{
// Start main task
xTaskCreate(altitudeTask, (const char *)"Altitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
xTaskCreate(altitudeTask, "Altitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ALTITUDE, taskHandle);
return 0;

View File

@ -145,7 +145,7 @@ static const struct pios_board_info *bdinfo = &pios_board_info_blob;
int32_t AttitudeStart(void)
{
// Start main task
xTaskCreate(AttitudeTask, (const char *)"Attitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
xTaskCreate(AttitudeTask, "Attitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ATTITUDE, taskHandle);
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);

View File

@ -231,7 +231,7 @@ int32_t AttitudeStart(void)
gpsVelQueue = xQueueCreate(1, sizeof(UAVObjEvent));
// Start main task
xTaskCreate(AttitudeTask, (const char *)"Attitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &attitudeTaskHandle);
xTaskCreate(AttitudeTask, "Attitude", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &attitudeTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_ATTITUDE, attitudeTaskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);

View File

@ -78,9 +78,9 @@ static int32_t comUsbBridgeStart(void)
{
if (bridge_enabled) {
// Start tasks
xTaskCreate(com2UsbBridgeTask, (const char *)"Com2UsbBridge", C2U_STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &com2UsbBridgeTaskHandle);
xTaskCreate(com2UsbBridgeTask, "Com2UsbBridge", C2U_STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &com2UsbBridgeTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_COM2USBBRIDGE, com2UsbBridgeTaskHandle);
xTaskCreate(usb2ComBridgeTask, (const char *)"Usb2ComBridge", U2C_STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &usb2ComBridgeTaskHandle);
xTaskCreate(usb2ComBridgeTask, "Usb2ComBridge", U2C_STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &usb2ComBridgeTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_USB2COMBRIDGE, usb2ComBridgeTaskHandle);
return 0;
}

View File

@ -81,7 +81,7 @@ int32_t MagBaroStart()
{
if (magbaroEnabled) {
// Start main task
xTaskCreate(magbaroTask, (const char *)"MagBaro", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
xTaskCreate(magbaroTask, "MagBaro", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_MAGBARO, taskHandle);
return 0;
}

View File

@ -94,7 +94,7 @@ int32_t FixedWingPathFollowerStart()
{
if (followerEnabled) {
// Start main task
xTaskCreate(pathfollowerTask, (const char *)"PathFollower", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle);
xTaskCreate(pathfollowerTask, "PathFollower", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_PATHFOLLOWER, pathfollowerTaskHandle);
}

View File

@ -111,7 +111,7 @@ int32_t GPSStart(void)
if (gpsEnabled) {
if (gpsPort) {
// Start gps task
xTaskCreate(gpsTask, (const char *)"GPS", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &gpsTaskHandle);
xTaskCreate(gpsTask, "GPS", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &gpsTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_GPS, gpsTaskHandle);
return 0;
}

View File

@ -80,7 +80,7 @@ int32_t OPLinkModStart(void)
stackOverflow = false;
mallocFailed = false;
// Create oplink system task
xTaskCreate(systemTask, (const char *)"OPLink", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &systemTaskHandle);
xTaskCreate(systemTask, "OPLink", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &systemTaskHandle);
// Register task
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);

View File

@ -55,7 +55,7 @@ static uint32_t timeOfLastUpdateMs;
int32_t WavPlayerStart(void)
{
// Start WavPlayer task
xTaskCreate(WavPlayerTask, (const char *)"WavPlayer", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &WavPlayerTaskHandle);
xTaskCreate(WavPlayerTask, "WavPlayer", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &WavPlayerTaskHandle);
return 0;
}

View File

@ -2404,7 +2404,7 @@ int32_t osdgenStart(void)
{
// Start gps task
vSemaphoreCreateBinary(osdSemaphore);
xTaskCreate(osdgenTask, (const char *)"OSDGEN", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &osdgenTaskHandle);
xTaskCreate(osdgenTask, "OSDGEN", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &osdgenTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_OSDGEN, osdgenTaskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_OSDGEN);

View File

@ -75,7 +75,7 @@ enum osd_pkt_type {
int32_t osdinputStart(void)
{
// Start osdinput task
xTaskCreate(osdinputTask, (const char *)"OSDINPUT", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &osdinputTaskHandle);
xTaskCreate(osdinputTask, "OSDINPUT", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &osdinputTaskHandle);
return 0;
}

View File

@ -186,23 +186,23 @@ static int32_t RadioComBridgeStart(void)
ObjectPersistenceConnectCallback(&objectPersistenceUpdatedCb);
// Start the primary tasks for receiving/sending UAVTalk packets from the GCS.
xTaskCreate(telemetryTxTask, (const char *)"telemetryTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
xTaskCreate(telemetryRxTask, (const char *)"telemetryRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryRxTaskHandle));
xTaskCreate(telemetryTxTask, "telemetryTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryTxTaskHandle));
xTaskCreate(telemetryRxTask, "telemetryRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->telemetryRxTaskHandle));
if (PIOS_PPM_RECEIVER != 0) {
xTaskCreate(PPMInputTask, (const char *)"PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->PPMInputTaskHandle));
xTaskCreate(PPMInputTask, "PPMInputTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->PPMInputTaskHandle));
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_PPMINPUT);
#endif
}
if (!data->parseUAVTalk) {
// If the user wants raw serial communication, we need to spawn another thread to handle it.
xTaskCreate(serialRxTask, (const char *)"serialRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->serialRxTaskHandle));
xTaskCreate(serialRxTask, "serialRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->serialRxTaskHandle));
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_SERIALRX);
#endif
}
xTaskCreate(radioTxTask, (const char *)"radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
xTaskCreate(radioRxTask, (const char *)"radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
xTaskCreate(radioTxTask, "radioTxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioTxTaskHandle));
xTaskCreate(radioRxTask, "radioRxTask", STACK_SIZE_BYTES, NULL, TASK_PRIORITY, &(data->radioRxTaskHandle));
// Register the watchdog timers.
#ifdef PIOS_INCLUDE_WDG

View File

@ -110,7 +110,7 @@ static bool updateRcvrActivity(struct rcvr_activity_fsm *fsm);
int32_t ReceiverStart()
{
// Start main task
xTaskCreate(receiverTask, (const char *)"Receiver", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
xTaskCreate(receiverTask, "Receiver", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &taskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_RECEIVER, taskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);

View File

@ -134,7 +134,7 @@ int32_t SensorsInitialize(void)
int32_t SensorsStart(void)
{
// Start main task
xTaskCreate(SensorsTask, (const char *)"Sensors", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &sensorsTaskHandle);
xTaskCreate(SensorsTask, "Sensors", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &sensorsTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_SENSORS, sensorsTaskHandle);
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_RegisterFlag(PIOS_WDG_SENSORS);

View File

@ -120,7 +120,7 @@ int32_t SystemModStart(void)
stackOverflow = STACKOVERFLOW_NONE;
mallocFailed = false;
// Create system task
xTaskCreate(systemTask, (const char *)"System", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &systemTaskHandle);
xTaskCreate(systemTask, "System", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &systemTaskHandle);
// Register task
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);

View File

@ -124,13 +124,13 @@ int32_t TelemetryStart(void)
GCSTelemetryStatsConnectQueue(priorityQueue);
// Start telemetry tasks
xTaskCreate(telemetryTxTask, (const char *)"TelTx", STACK_SIZE_TX_BYTES / 4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
xTaskCreate(telemetryTxTask, "TelTx", STACK_SIZE_TX_BYTES / 4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
xTaskCreate(telemetryRxTask, (const char *)"TelRx", STACK_SIZE_RX_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
xTaskCreate(telemetryRxTask, "TelRx", STACK_SIZE_RX_BYTES / 4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
#ifdef PIOS_INCLUDE_RFM22B
xTaskCreate(radioRxTask, (const char *)"RadioRx", STACK_SIZE_RADIO_RX_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
xTaskCreate(radioRxTask, "RadioRx", STACK_SIZE_RADIO_RX_BYTES / 4, NULL, TASK_PRIORITY_RADRX, &radioRxTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_RADIORX, radioRxTaskHandle);
#endif

View File

@ -112,7 +112,7 @@ int32_t VtolPathFollowerStart()
{
if (vtolpathfollower_enabled) {
// Start main task
xTaskCreate(vtolPathFollowerTask, (const char *)"VtolPathFollower", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle);
xTaskCreate(vtolPathFollowerTask, "VtolPathFollower", STACK_SIZE_BYTES / 4, NULL, TASK_PRIORITY, &pathfollowerTaskHandle);
PIOS_TASK_MONITOR_RegisterTask(TASKINFO_RUNNING_PATHFOLLOWER, pathfollowerTaskHandle);
}

View File

@ -465,7 +465,7 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu
pios_rfm22_inject_event(rfm22b_dev, RADIO_EVENT_INITIALIZE, false);
// Start the driver task. This task controls the radio state machine and removed all of the IO from the IRQ handler.
xTaskCreate(pios_rfm22_task, (const char *)"PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void *)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle));
xTaskCreate(pios_rfm22_task, "PIOS_RFM22B_Task", STACK_SIZE_BYTES, (void *)rfm22b_dev, TASK_PRIORITY, &(rfm22b_dev->taskHandle));
return 0;
}

View File

@ -139,7 +139,7 @@ int32_t PIOS_UDP_Init(uint32_t *udp_id, const struct pios_udp_cfg *cfg)
/* Create transmit thread for this connection */
#if defined(PIOS_INCLUDE_FREERTOS)
// ( pdTASK_CODE pvTaskCode, const portCHAR * const pcName, unsigned portSHORT usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pvCreatedTask );
xTaskCreate((pdTASK_CODE)PIOS_UDP_RxThread, (const char *)"UDP_Rx_Thread", 1024, (void *)udp_dev, (tskIDLE_PRIORITY + 1), &udp_dev->rxThread);
xTaskCreate((pdTASK_CODE)PIOS_UDP_RxThread, "UDP_Rx_Thread", 1024, (void *)udp_dev, (tskIDLE_PRIORITY + 1), &udp_dev->rxThread);
#else
pthread_create(&udp_dev->rxThread, NULL, PIOS_UDP_RxThread, (void *)udp_dev);
#endif

View File

@ -97,7 +97,7 @@ int main()
/* For Revolution we use a FreeRTOS task to bring up the system so we can */
/* always rely on FreeRTOS primitive */
result = xTaskCreate(initTask, (const char *)"init",
result = xTaskCreate(initTask, "init",
INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY,
&initTaskHandle);
PIOS_Assert(result == pdPASS);

View File

@ -189,7 +189,7 @@ int main()
/* For Revolution we use a FreeRTOS task to bring up the system so we can */
/* always rely on FreeRTOS primitive */
result = xTaskCreate(initTask, (const char *)"init",
result = xTaskCreate(initTask, "init",
INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY,
&initTaskHandle);
PIOS_Assert(result == pdPASS);

View File

@ -97,7 +97,7 @@ int main()
/* For Revolution we use a FreeRTOS task to bring up the system so we can */
/* always rely on FreeRTOS primitive */
result = xTaskCreate(initTask, (const char *)"init",
result = xTaskCreate(initTask, "init",
INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY,
&initTaskHandle);
PIOS_Assert(result == pdPASS);

View File

@ -96,7 +96,7 @@ int main()
/* For Revolution we use a FreeRTOS task to bring up the system so we can */
/* always rely on FreeRTOS primitive */
result = xTaskCreate(initTask, (const char *)"init",
result = xTaskCreate(initTask, "init",
INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY,
&initTaskHandle);
PIOS_Assert(result == pdPASS);

View File

@ -97,7 +97,7 @@ int main()
/* For Revolution we use a FreeRTOS task to bring up the system so we can */
/* always rely on FreeRTOS primitive */
result = xTaskCreate(initTask, (const char *)"init",
result = xTaskCreate(initTask, "init",
INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY,
&initTaskHandle);
PIOS_Assert(result == pdPASS);