forked from Archive/PX4-Autopilot
Adjusted to renaming of TCB in NuttX
This commit is contained in:
parent
4db739b5e1
commit
63d460160c
|
@ -1,9 +1,8 @@
|
|||
/****************************************************************************
|
||||
* configs/px4fmu/src/up_leds.c
|
||||
* arch/arm/src/board/up_leds.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -15,7 +14,7 @@
|
|||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
|
@ -34,18 +33,26 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file cpuload.c
|
||||
*
|
||||
* Measurement of CPU load of each individual task.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
|
||||
*/
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/sched.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <arch/arch.h>
|
||||
|
||||
#include <debug.h>
|
||||
|
||||
#include <sys/time.h>
|
||||
#include <sched.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
@ -54,26 +61,13 @@
|
|||
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT void sched_note_start(FAR _TCB *tcb);
|
||||
__EXPORT void sched_note_stop(FAR _TCB *tcb);
|
||||
__EXPORT void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
|
||||
|
||||
/****************************************************************************
|
||||
* Name:
|
||||
****************************************************************************/
|
||||
__EXPORT void sched_note_start(FAR struct tcb_s *tcb);
|
||||
__EXPORT void sched_note_stop(FAR struct tcb_s *tcb);
|
||||
__EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb);
|
||||
|
||||
__EXPORT struct system_load_s system_load;
|
||||
|
||||
extern FAR _TCB *sched_gettcb(pid_t pid);
|
||||
extern FAR struct _TCB *sched_gettcb(pid_t pid);
|
||||
|
||||
void cpuload_initialize_once()
|
||||
{
|
||||
|
@ -109,7 +103,7 @@ void cpuload_initialize_once()
|
|||
// }
|
||||
}
|
||||
|
||||
void sched_note_start(FAR _TCB *tcb)
|
||||
void sched_note_start(FAR struct tcb_s *tcb)
|
||||
{
|
||||
/* search first free slot */
|
||||
int i;
|
||||
|
@ -128,7 +122,7 @@ void sched_note_start(FAR _TCB *tcb)
|
|||
}
|
||||
}
|
||||
|
||||
void sched_note_stop(FAR _TCB *tcb)
|
||||
void sched_note_stop(FAR struct tcb_s *tcb)
|
||||
{
|
||||
int i;
|
||||
|
||||
|
@ -145,7 +139,7 @@ void sched_note_stop(FAR _TCB *tcb)
|
|||
}
|
||||
}
|
||||
|
||||
void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb)
|
||||
void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pToTcb)
|
||||
{
|
||||
uint64_t new_time = hrt_absolute_time();
|
||||
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -43,7 +43,7 @@ struct system_load_taskinfo_s {
|
|||
uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
|
||||
uint64_t curr_start_time; ///< Start time of the current scheduling slot
|
||||
uint64_t start_time; ///< FIRST start time of task
|
||||
FAR struct _TCB *tcb; ///<
|
||||
FAR struct tcb_s *tcb; ///<
|
||||
bool valid; ///< Task is currently active / valid
|
||||
};
|
||||
|
||||
|
@ -60,4 +60,6 @@ __EXPORT extern struct system_load_s system_load;
|
|||
|
||||
__EXPORT void cpuload_initialize_once(void);
|
||||
|
||||
__END_DECLS
|
||||
|
||||
#endif
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -61,7 +61,7 @@ const char *
|
|||
getprogname(void)
|
||||
{
|
||||
#if CONFIG_TASK_NAME_SIZE > 0
|
||||
_TCB *thisproc = sched_self();
|
||||
FAR struct tcb_s *thisproc = sched_self();
|
||||
|
||||
return thisproc->name;
|
||||
#else
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
|
||||
#include "systemlib.h"
|
||||
|
||||
static void kill_task(FAR _TCB *tcb, FAR void *arg);
|
||||
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
|
||||
|
||||
void killall()
|
||||
{
|
||||
|
@ -60,7 +60,7 @@ void killall()
|
|||
sched_foreach(kill_task, NULL);
|
||||
}
|
||||
|
||||
static void kill_task(FAR _TCB *tcb, FAR void *arg)
|
||||
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
|
||||
{
|
||||
kill(tcb->pid, SIGUSR1);
|
||||
}
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -36,6 +36,8 @@
|
|||
* @file top.c
|
||||
* Tool similar to UNIX top command
|
||||
* @see http://en.wikipedia.org/wiki/Top_unix
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
|
Loading…
Reference in New Issue