3 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN 12 #include <uORB/uORB.h> 13 #include <uORB/topics/safety.h> 14 #include <systemlib/board_serial.h> 15 #include <drivers/drv_gpio.h> 53 v = fcntl(fd, F_GETFL, 0);
54 fcntl(fd, F_SETFL, v & ~O_NONBLOCK);
64 nsh_consolemain(0,
nullptr);
76 #if !HAL_HAVE_SAFETY_SWITCH 86 struct safety_s safety;
90 if (!safety.safety_switch_available) {
93 if (safety.safety_off) {
102 ts.tv_sec = time_utc_usec/1000000ULL;
103 ts.tv_nsec = (time_utc_usec % 1000000ULL) * 1000ULL;
104 clock_settime(CLOCK_REALTIME, &ts);
112 uint8_t serialid[12];
113 memset(serialid, 0,
sizeof(serialid));
115 #if defined(CONFIG_ARCH_BOARD_VRBRAIN_V45) 116 const char *board_type =
"VRBRAINv45";
117 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) 118 const char *board_type =
"VRBRAINv51";
119 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52) 120 const char *board_type =
"VRBRAINv52";
121 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E) 122 const char *board_type =
"VRBRAINv52E";
123 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51) 124 const char *board_type =
"VRUBRAINv51";
125 #elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52) 126 const char *board_type =
"VRUBRAINv52";
127 #elif defined(CONFIG_ARCH_BOARD_VRCORE_V10) 128 const char *board_type =
"VRCOREv10";
129 #elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54) 130 const char *board_type =
"VRBRAINv54";
134 snprintf(buf, 40,
"%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
136 (
unsigned)serialid[0], (
unsigned)serialid[1], (
unsigned)serialid[2], (
unsigned)serialid[3],
137 (
unsigned)serialid[4], (
unsigned)serialid[5], (
unsigned)serialid[6], (
unsigned)serialid[7],
138 (
unsigned)serialid[8], (
unsigned)serialid[9], (
unsigned)serialid[10],(
unsigned)serialid[11]);
147 return mallinfo().fordblks;
199 if (now -
_heater.last_update_ms < 1000) {
209 const float kI = 0.3f;
210 const float kP = 200.0f;
216 float err = target - current;
218 _heater.integrator += kI * err;
229 ioctl(
_heater.fd, GPIO_SET_HEATER_DUTY_CYCLE, (
unsigned)output);
274 #endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
struct VRBRAIN::VRBRAINUtil::@118 _heater
bool run_debug_shell(AP_HAL::BetterStream *stream)
void get_board_serial(uint8_t *serialid)
void perf_end(perf_counter_t) override
void perf_begin(perf_counter_t) override
bool get_system_id(char buf[40])
void set_imu_temp(float current) override
void * calloc(size_t nmemb, size_t size)
enum safety_state safety_switch_state(void)
perf_counter_t perf_alloc(perf_counter_type t, const char *name) override
virtual void printf(const char *,...) FMT_PRINTF(2
void * fat_dma_alloc(size_t)
int close(int fileno)
POSIX Close a file with fileno handel.
bool _vrbrain_thread_should_exit
void set_imu_target_temp(int8_t *target) override
void set_system_clock(uint64_t time_utc_usec)
float constrain_float(const float amt, const float low, const float high)
void * malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) override
int snprintf(char *str, size_t size, const char *format,...)
uint32_t available_memory(void) override
void fat_dma_free(void *, size_t)
void perf_count(perf_counter_t) override
void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) override