forked from Archive/PX4-Autopilot
Merge branch 'master' of github.com:PX4/Firmware into ardrone
This commit is contained in:
commit
eaa431e5ce
|
@ -103,7 +103,8 @@ class uploader(object):
|
|||
REBOOT = chr(0x30)
|
||||
|
||||
INFO_BL_REV = chr(1) # bootloader protocol revision
|
||||
BL_REV = 2 # supported bootloader protocol
|
||||
BL_REV_MIN = 2 # minimum supported bootloader protocol
|
||||
BL_REV_MAX = 3 # maximum supported bootloader protocol
|
||||
INFO_BOARD_ID = chr(2) # board type
|
||||
INFO_BOARD_REV = chr(3) # board revision
|
||||
INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
|
||||
|
@ -240,7 +241,8 @@ class uploader(object):
|
|||
|
||||
# get the bootloader protocol ID first
|
||||
bl_rev = self.__getInfo(uploader.INFO_BL_REV)
|
||||
if bl_rev != uploader.BL_REV:
|
||||
if (bl_rev < uploader.BL_REV_MIN) or (bl_rev > uploader.BL_REV_MAX):
|
||||
print("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV)
|
||||
raise RuntimeError("Bootloader protocol mismatch")
|
||||
|
||||
self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
|
||||
|
|
|
@ -329,4 +329,10 @@
|
|||
discussed at http://www.drdobbs.com/web-development/\
|
||||
an-embeddable-lightweight-xml-rpc-server/184405364. Contributed by
|
||||
Max Holtzberg.
|
||||
|
||||
* apps/netutils/uip_listenon.c: Logic in uip_server.c that creates
|
||||
the listening socket was moved to this new file to support re-use.
|
||||
Contributed by Kate.
|
||||
* apps/netutils/webserver/httpd.c: The option CONFIG_NETUTILS_HTTPD_SINGLECONNECT
|
||||
can now be used to limit the server to a single thread. Option
|
||||
CONFIG_NETUTILS_HTTPD_TIMEOUT can be used to generate HTTP 408 errors.
|
||||
Both from Kate.
|
||||
|
|
195
apps/gps/gps.c
195
apps/gps/gps.c
|
@ -38,7 +38,6 @@
|
|||
*/
|
||||
|
||||
#include "gps.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
|
@ -58,7 +57,7 @@
|
|||
#include <v1.0/common/mavlink.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_should_exit; /**< Deamon status flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
|
@ -82,16 +81,6 @@ int gps_thread_main(int argc, char *argv[]);
|
|||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "\tusage: %s -d devicename -b baudrate -m mode\n\tmodes are:\n\t\tubx\n\t\tmtkcustom\n\t\tnmea\n\t\tall\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
@ -115,7 +104,6 @@ enum GPS_MODES {
|
|||
};
|
||||
|
||||
|
||||
|
||||
#define AUTO_DETECTION_COUNT 8
|
||||
const int autodetection_baudrates[] = {B9600, B38400, B38400, B9600, B9600, B38400, B9600, B38400};
|
||||
const enum GPS_MODES autodetection_gpsmodes[] = {GPS_MODE_UBX, GPS_MODE_MTK, GPS_MODE_UBX, GPS_MODE_MTK, GPS_MODE_UBX, GPS_MODE_MTK, GPS_MODE_NMEA, GPS_MODE_NMEA}; //nmea is the fall-back if nothing else works, therefore we try the standard modes again before finally trying nmea
|
||||
|
@ -125,40 +113,9 @@ const enum GPS_MODES autodetection_gpsmodes[] = {GPS_MODE_UBX, GPS_MODE_MTK, GPS
|
|||
****************************************************************************/
|
||||
int open_port(char *port);
|
||||
|
||||
void close_port(int fd);
|
||||
void close_port(int *fd);
|
||||
|
||||
void setup_port(char *device, int speed, int *fd)
|
||||
{
|
||||
|
||||
/* open port (baud rate is set in defconfig file) */
|
||||
*fd = open_port(device);
|
||||
|
||||
if (*fd != -1) {
|
||||
if (gps_verbose) printf("[gps] Port opened: %s at %d speed\r\n", device, speed);
|
||||
|
||||
} else {
|
||||
fprintf(stderr, "[gps] Could not open port, exiting gps app!\r\n");
|
||||
fflush(stdout);
|
||||
}
|
||||
|
||||
/* Try to set baud rate */
|
||||
struct termios uart_config;
|
||||
int termios_state;
|
||||
|
||||
if ((termios_state = tcgetattr(*fd, &uart_config)) < 0) {
|
||||
fprintf(stderr, "[gps] ERROR getting baudrate / termios config for %s: %d\r\n", device, termios_state);
|
||||
close(*fd);
|
||||
}
|
||||
|
||||
/* Set baud rate */
|
||||
cfsetispeed(&uart_config, speed);
|
||||
cfsetospeed(&uart_config, speed);
|
||||
|
||||
if ((termios_state = tcsetattr(*fd, TCSANOW, &uart_config)) < 0) {
|
||||
fprintf(stderr, "[gps] ERROR setting baudrate / termios config for %s (tcsetattr)\r\n", device);
|
||||
close(*fd);
|
||||
}
|
||||
}
|
||||
void setup_port(char *device, int speed, int *fd);
|
||||
|
||||
|
||||
/**
|
||||
|
@ -195,7 +152,7 @@ int gps_main(int argc, char *argv[])
|
|||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
printf("\gps is running\n");
|
||||
printf("\tgps is running\n");
|
||||
} else {
|
||||
printf("\tgps not started\n");
|
||||
}
|
||||
|
@ -215,7 +172,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
printf("[gps] Initialized. Searching for GPS receiver..\n");
|
||||
|
||||
/* default values */
|
||||
const char *commandline_usage = "\tusage: %s -d devicename -b baudrate -m mode\n\tmodes are:\n\t\tubx\n\t\tmtkcustom\n\t\tnmea\n\t\tall\n";
|
||||
const char *commandline_usage = "\tusage: %s {start|stop|status} -d devicename -b baudrate -m mode\n\tmodes are:\n\t\tubx\n\t\tmtkcustom\n\t\tnmea\n\t\tall\n";
|
||||
char *device = "/dev/ttyS3";
|
||||
char mode[10];
|
||||
strcpy(mode, "all");
|
||||
|
@ -235,6 +192,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
for (i = 0; i < argc; i++) {
|
||||
if (strcmp(argv[i], "-h") == 0 || strcmp(argv[i], "--help") == 0) { //device set
|
||||
printf(commandline_usage, argv[0]);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -244,6 +202,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
|
||||
} else {
|
||||
printf(commandline_usage, argv[0]);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
@ -254,6 +213,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
|
||||
} else {
|
||||
printf(commandline_usage, argv[0]);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
@ -264,6 +224,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
|
||||
} else {
|
||||
printf(commandline_usage, argv[0]);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
@ -274,6 +235,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
|
||||
} else {
|
||||
printf(commandline_usage, argv[0]);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
@ -294,45 +256,25 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
case -1: gps_baud_try_all = true; break;
|
||||
|
||||
case 0: current_gps_speed = B0; break;
|
||||
|
||||
case 50: current_gps_speed = B50; break;
|
||||
|
||||
case 75: current_gps_speed = B75; break;
|
||||
|
||||
case 110: current_gps_speed = B110; break;
|
||||
|
||||
case 134: current_gps_speed = B134; break;
|
||||
|
||||
case 150: current_gps_speed = B150; break;
|
||||
|
||||
case 200: current_gps_speed = B200; break;
|
||||
|
||||
case 300: current_gps_speed = B300; break;
|
||||
|
||||
case 600: current_gps_speed = B600; break;
|
||||
|
||||
case 1200: current_gps_speed = B1200; break;
|
||||
|
||||
case 1800: current_gps_speed = B1800; break;
|
||||
|
||||
case 2400: current_gps_speed = B2400; break;
|
||||
|
||||
case 4800: current_gps_speed = B4800; break;
|
||||
|
||||
case 9600: current_gps_speed = B9600; break;
|
||||
|
||||
case 19200: current_gps_speed = B19200; break;
|
||||
|
||||
case 38400: current_gps_speed = B38400; break;
|
||||
|
||||
case 57600: current_gps_speed = B57600; break;
|
||||
|
||||
case 115200: current_gps_speed = B115200; break;
|
||||
|
||||
case 230400: current_gps_speed = B230400; break;
|
||||
|
||||
case 460800: current_gps_speed = B460800; break;
|
||||
|
||||
case 921600: current_gps_speed = B921600; break;
|
||||
|
||||
default:
|
||||
|
@ -359,9 +301,12 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
} else {
|
||||
fprintf(stderr, "\t[gps] Invalid mode argument\n");
|
||||
printf(commandline_usage);
|
||||
thread_running = false;
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Declare file descriptor for gps here, open port later in setup_port */
|
||||
int fd;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
/* Infinite retries or break if retry == false */
|
||||
|
@ -388,13 +333,12 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
* if the gps was once running the wtachdog thread will not return but instead try to reconfigure the gps (depending on the mode/protocol)
|
||||
*/
|
||||
|
||||
if (current_gps_mode == GPS_MODE_UBX) { //TODO: make a small enum with all modes to avoid all the strcpy
|
||||
if (current_gps_mode == GPS_MODE_UBX) {
|
||||
|
||||
if (gps_verbose) printf("[gps] Trying UBX mode at %d baud\n", current_gps_speed);
|
||||
|
||||
mavlink_log_info(mavlink_fd, "GPS: trying to connect to a ubx module");
|
||||
mavlink_log_info(mavlink_fd, "[gps] trying to connect to a ubx module");
|
||||
|
||||
int fd;
|
||||
setup_port(device, current_gps_speed, &fd);
|
||||
|
||||
/* start ubx thread and watchdog */
|
||||
|
@ -411,13 +355,18 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
pthread_attr_t ubx_loop_attr;
|
||||
pthread_attr_init(&ubx_loop_attr);
|
||||
pthread_attr_setstacksize(&ubx_loop_attr, 3000);
|
||||
pthread_create(&ubx_thread, &ubx_loop_attr, ubx_loop, (void *)&fd);
|
||||
|
||||
struct arg_struct args;
|
||||
args.fd_ptr = &fd;
|
||||
args.thread_should_exit_ptr = &thread_should_exit;
|
||||
|
||||
pthread_create(&ubx_thread, &ubx_loop_attr, ubx_loop, (void *)&args);
|
||||
sleep(2); // XXX TODO Check if this is too short, try to lower sleeps in UBX driver
|
||||
|
||||
pthread_attr_t ubx_wd_attr;
|
||||
pthread_attr_init(&ubx_wd_attr);
|
||||
pthread_attr_setstacksize(&ubx_wd_attr, 1400);
|
||||
int pthread_create_res = pthread_create(&ubx_watchdog_thread, &ubx_wd_attr, ubx_watchdog_loop, (void *)&fd);
|
||||
int pthread_create_res = pthread_create(&ubx_watchdog_thread, &ubx_wd_attr, ubx_watchdog_loop, (void *)&args);
|
||||
|
||||
if (pthread_create_res != 0) fprintf(stderr, "[gps] ERROR: could not create ubx watchdog thread, pthread_create =%d\n", pthread_create_res);
|
||||
|
||||
|
@ -432,18 +381,23 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
|
||||
gps_mode_success = true;
|
||||
terminate_gps_thread = false;
|
||||
|
||||
/* maybe the watchdog was stopped through the thread_should_exit flag */
|
||||
} else if (thread_should_exit) {
|
||||
pthread_join(ubx_thread, NULL);
|
||||
if (gps_verbose) printf("[gps] ubx watchdog and ubx loop threads have been terminated, exiting.");
|
||||
close(mavlink_fd);
|
||||
close_port(&fd);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
close_port(fd);
|
||||
}
|
||||
|
||||
if (current_gps_mode == GPS_MODE_MTK) {
|
||||
close_port(&fd);
|
||||
} else if (current_gps_mode == GPS_MODE_MTK) {
|
||||
if (gps_verbose) printf("[gps] trying MTK binary mode at %d baud\n", current_gps_speed);
|
||||
|
||||
mavlink_log_info(mavlink_fd, "[gps] trying to connect to a MTK module");
|
||||
|
||||
|
||||
int fd;
|
||||
setup_port(device, current_gps_speed, &fd);
|
||||
|
||||
/* start mtk thread and watchdog */
|
||||
|
@ -463,9 +417,14 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
pthread_attr_t mtk_loop_attr;
|
||||
pthread_attr_init(&mtk_loop_attr);
|
||||
pthread_attr_setstacksize(&mtk_loop_attr, 2048);
|
||||
pthread_create(&mtk_thread, &mtk_loop_attr, mtk_loop, (void *)&fd);
|
||||
|
||||
struct arg_struct args;
|
||||
args.fd_ptr = &fd;
|
||||
args.thread_should_exit_ptr = &thread_should_exit;
|
||||
|
||||
pthread_create(&mtk_thread, &mtk_loop_attr, mtk_loop, (void *)&args);
|
||||
sleep(2);
|
||||
pthread_create(&mtk_watchdog_thread, NULL, mtk_watchdog_loop, (void *)&fd);
|
||||
pthread_create(&mtk_watchdog_thread, NULL, mtk_watchdog_loop, (void *)&args);
|
||||
|
||||
/* wait for threads to complete */
|
||||
pthread_join(mtk_watchdog_thread, (void *)&fd);
|
||||
|
@ -483,16 +442,14 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
terminate_gps_thread = false;
|
||||
}
|
||||
|
||||
close_port(fd);
|
||||
close_port(&fd);
|
||||
|
||||
}
|
||||
|
||||
if (current_gps_mode == GPS_MODE_NMEA) {
|
||||
} else if (current_gps_mode == GPS_MODE_NMEA) {
|
||||
if (gps_verbose) printf("[gps] Trying NMEA mode at %d baud\n", current_gps_speed);
|
||||
|
||||
mavlink_log_info(mavlink_fd, "[gps] trying to connect to a NMEA module");
|
||||
|
||||
int fd;
|
||||
|
||||
setup_port(device, current_gps_speed, &fd);
|
||||
|
||||
/* start nmea thread and watchdog */
|
||||
|
@ -509,9 +466,14 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
pthread_attr_t nmea_loop_attr;
|
||||
pthread_attr_init(&nmea_loop_attr);
|
||||
pthread_attr_setstacksize(&nmea_loop_attr, 4096);
|
||||
pthread_create(&nmea_thread, &nmea_loop_attr, nmea_loop, (void *)&fd);
|
||||
|
||||
struct arg_struct args;
|
||||
args.fd_ptr = &fd;
|
||||
args.thread_should_exit_ptr = &thread_should_exit;
|
||||
|
||||
pthread_create(&nmea_thread, &nmea_loop_attr, nmea_loop, (void *)&args);
|
||||
sleep(2);
|
||||
pthread_create(&nmea_watchdog_thread, NULL, nmea_watchdog_loop, (void *)&fd);
|
||||
pthread_create(&nmea_watchdog_thread, NULL, nmea_watchdog_loop, (void *)&args);
|
||||
|
||||
/* wait for threads to complete */
|
||||
pthread_join(nmea_watchdog_thread, (void *)&fd);
|
||||
|
@ -526,7 +488,15 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
terminate_gps_thread = false;
|
||||
}
|
||||
|
||||
close_port(fd);
|
||||
close_port(&fd);
|
||||
}
|
||||
|
||||
/* exit quickly if stop command has been received */
|
||||
if (thread_should_exit) {
|
||||
printf("[gps] stopped, exiting.\n");
|
||||
close(mavlink_fd);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* if both, mode and baud is set by argument, we only need one loop*/
|
||||
|
@ -534,6 +504,7 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
break;
|
||||
}
|
||||
|
||||
|
||||
if (retry) {
|
||||
printf("[gps] No configuration was successful, retrying in %d seconds \n", RETRY_INTERVAL_SECONDS);
|
||||
mavlink_log_info(mavlink_fd, "[gps] No configuration was successful, retrying...");
|
||||
|
@ -549,13 +520,21 @@ int gps_thread_main(int argc, char *argv[]) {
|
|||
sleep(RETRY_INTERVAL_SECONDS);
|
||||
}
|
||||
|
||||
close(mavlink_fd);
|
||||
|
||||
printf("[gps] exiting.\n");
|
||||
|
||||
close(mavlink_fd);
|
||||
thread_running = false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
static void usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "\tusage: gps {start|status|stop} -d devicename -b baudrate -m mode\n\tmodes are:\n\t\tubx\n\t\tmtkcustom\n\t\tnmea\n\t\tall\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
int open_port(char *port)
|
||||
{
|
||||
int fd; /**< File descriptor for the gps port */
|
||||
|
@ -566,11 +545,39 @@ int open_port(char *port)
|
|||
}
|
||||
|
||||
|
||||
void close_port(int fd)
|
||||
void close_port(int *fd)
|
||||
{
|
||||
/* Close serial port */
|
||||
close(fd);
|
||||
close(*fd);
|
||||
}
|
||||
|
||||
void setup_port(char *device, int speed, int *fd)
|
||||
{
|
||||
/* open port (baud rate is set in defconfig file) */
|
||||
*fd = open_port(device);
|
||||
|
||||
if (*fd != -1) {
|
||||
if (gps_verbose) printf("[gps] Port opened: %s at %d speed\r\n", device, speed);
|
||||
|
||||
} else {
|
||||
fprintf(stderr, "[gps] Could not open port, exiting gps app!\r\n");
|
||||
fflush(stdout);
|
||||
}
|
||||
|
||||
/* Try to set baud rate */
|
||||
struct termios uart_config;
|
||||
int termios_state;
|
||||
|
||||
if ((termios_state = tcgetattr(*fd, &uart_config)) < 0) {
|
||||
fprintf(stderr, "[gps] ERROR getting baudrate / termios config for %s: %d\r\n", device, termios_state);
|
||||
close(*fd);
|
||||
}
|
||||
if (gps_verbose) printf("[gps] Try to set baud rate %d now\n",speed);
|
||||
/* Set baud rate */
|
||||
cfsetispeed(&uart_config, speed);
|
||||
cfsetospeed(&uart_config, speed);
|
||||
if ((termios_state = tcsetattr(*fd, TCSANOW, &uart_config)) < 0) {
|
||||
fprintf(stderr, "[gps] ERROR setting baudrate / termios config for %s (tcsetattr)\r\n", device);
|
||||
close(*fd);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -6,15 +6,13 @@
|
|||
*/
|
||||
|
||||
#ifndef GPS_H_
|
||||
#define GPS_H_
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
int gps_fd;
|
||||
|
||||
//extern gps_bin_ubx_state_t * ubx_state;
|
||||
#define GPS_H
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
struct arg_struct {
|
||||
int *fd_ptr;
|
||||
bool *thread_should_exit_ptr;
|
||||
};
|
||||
|
||||
#endif /* GPS_H_ */
|
||||
|
|
|
@ -35,12 +35,14 @@
|
|||
|
||||
/* @file MTK custom binary (3DR) protocol implementation */
|
||||
|
||||
#include "gps.h"
|
||||
#include "mtk.h"
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <pthread.h>
|
||||
#include <poll.h>
|
||||
#include <fcntl.h>
|
||||
#include <arch/board/up_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
@ -180,7 +182,7 @@ int mtk_parse(uint8_t b, char *gps_rx_buffer)
|
|||
|
||||
}
|
||||
|
||||
int read_gps_mtk(int fd, char *gps_rx_buffer, int buffer_size) // returns 1 if the thread should terminate
|
||||
int read_gps_mtk(int *fd, char *gps_rx_buffer, int buffer_size) // returns 1 if the thread should terminate
|
||||
{
|
||||
// printf("in read_gps_mtk\n");
|
||||
uint8_t ret = 0;
|
||||
|
@ -191,7 +193,7 @@ int read_gps_mtk(int fd, char *gps_rx_buffer, int buffer_size) // returns 1 if
|
|||
int gpsRxOverflow = 0;
|
||||
|
||||
struct pollfd fds;
|
||||
fds.fd = fd;
|
||||
fds.fd = *fd;
|
||||
fds.events = POLLIN;
|
||||
|
||||
// This blocks the task until there is something on the buffer
|
||||
|
@ -206,7 +208,7 @@ int read_gps_mtk(int fd, char *gps_rx_buffer, int buffer_size) // returns 1 if
|
|||
}
|
||||
|
||||
if (poll(&fds, 1, 1000) > 0) {
|
||||
if (read(fd, &c, 1) > 0) {
|
||||
if (read(*fd, &c, 1) > 0) {
|
||||
// printf("Read %x\n",c);
|
||||
if (rx_count >= buffer_size) {
|
||||
// The buffer is already full and we haven't found a valid NMEA sentence.
|
||||
|
@ -243,11 +245,11 @@ int read_gps_mtk(int fd, char *gps_rx_buffer, int buffer_size) // returns 1 if
|
|||
return ret;
|
||||
}
|
||||
|
||||
int configure_gps_mtk(int fd)
|
||||
int configure_gps_mtk(int *fd)
|
||||
{
|
||||
int success = 0;
|
||||
size_t result_write;
|
||||
result_write = write(fd, MEDIATEK_REFRESH_RATE_10HZ, strlen(MEDIATEK_REFRESH_RATE_10HZ));
|
||||
result_write = write(*fd, MEDIATEK_REFRESH_RATE_10HZ, strlen(MEDIATEK_REFRESH_RATE_10HZ));
|
||||
|
||||
if (result_write != strlen(MEDIATEK_REFRESH_RATE_10HZ)) {
|
||||
printf("[gps] Set update speed to 10 Hz failed\r\n");
|
||||
|
@ -258,7 +260,7 @@ int configure_gps_mtk(int fd)
|
|||
}
|
||||
|
||||
//set custom mode
|
||||
result_write = write(fd, MEDIATEK_CUSTOM_BINARY_MODE, strlen(MEDIATEK_CUSTOM_BINARY_MODE));
|
||||
result_write = write(*fd, MEDIATEK_CUSTOM_BINARY_MODE, strlen(MEDIATEK_CUSTOM_BINARY_MODE));
|
||||
|
||||
if (result_write != strlen(MEDIATEK_CUSTOM_BINARY_MODE)) {
|
||||
//global_data_send_subsystem_info(&mtk_present);
|
||||
|
@ -273,7 +275,7 @@ int configure_gps_mtk(int fd)
|
|||
return success;
|
||||
}
|
||||
|
||||
void *mtk_loop(void *arg)
|
||||
void *mtk_loop(void *args)
|
||||
{
|
||||
// int oldstate;
|
||||
// pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, oldstate);
|
||||
|
@ -282,8 +284,10 @@ void *mtk_loop(void *arg)
|
|||
/* Set thread name */
|
||||
prctl(PR_SET_NAME, "gps mtk read", getpid());
|
||||
|
||||
/* Retrieve file descriptor */
|
||||
int fd = *((int *)arg);
|
||||
/* Retrieve file descriptor and thread flag */
|
||||
struct arg_struct *arguments = (struct arg_struct *)args;
|
||||
int *fd = arguments->fd_ptr;
|
||||
bool *thread_should_exit = arguments->thread_should_exit_ptr;
|
||||
|
||||
/* Initialize gps stuff */
|
||||
// int buffer_size = 1000;
|
||||
|
@ -313,7 +317,7 @@ void *mtk_loop(void *arg)
|
|||
mtk_gps = &mtk_gps_d;
|
||||
orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), mtk_gps);
|
||||
|
||||
while (1) {
|
||||
while (!(*thread_should_exit)) {
|
||||
/* Parse a message from the gps receiver */
|
||||
if (OK == read_gps_mtk(fd, gps_rx_buffer, MTK_BUFFER_SIZE)) {
|
||||
|
||||
|
@ -321,15 +325,19 @@ void *mtk_loop(void *arg)
|
|||
orb_publish(ORB_ID(vehicle_gps_position), gps_handle, mtk_gps);
|
||||
|
||||
} else {
|
||||
/* de-advertise */
|
||||
close(gps_handle);
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
close(gps_handle);
|
||||
if(gps_verbose) printf("[gps] mtk loop is going to terminate\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void *mtk_watchdog_loop(void *arg)
|
||||
void *mtk_watchdog_loop(void *args)
|
||||
{
|
||||
// printf("in mtk watchdog loop\n");
|
||||
fflush(stdout);
|
||||
|
@ -337,8 +345,10 @@ void *mtk_watchdog_loop(void *arg)
|
|||
/* Set thread name */
|
||||
prctl(PR_SET_NAME, "gps mtk watchdog", getpid());
|
||||
|
||||
/* Retrieve file descriptor */
|
||||
int fd = *((int *)arg);
|
||||
/* Retrieve file descriptor and thread flag */
|
||||
struct arg_struct *arguments = (struct arg_struct *)args;
|
||||
int *fd = arguments->fd_ptr;
|
||||
bool *thread_should_exit = arguments->thread_should_exit_ptr;
|
||||
|
||||
bool mtk_healthy = false;
|
||||
|
||||
|
@ -349,7 +359,7 @@ void *mtk_watchdog_loop(void *arg)
|
|||
int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
|
||||
while (1) {
|
||||
while (!(*thread_should_exit)) {
|
||||
fflush(stdout);
|
||||
|
||||
/* if we have no update for a long time reconfigure gps */
|
||||
|
@ -416,8 +426,7 @@ void *mtk_watchdog_loop(void *arg)
|
|||
|
||||
usleep(MTK_WATCHDOG_WAIT_TIME_MICROSECONDS);
|
||||
}
|
||||
|
||||
if(gps_verbose) printf("[gps] mtk watchdog is going to terminate\n");
|
||||
close(mavlink_fd);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -87,12 +87,12 @@ void mtk_checksum(uint8_t b, uint8_t *ck_a, uint8_t *ck_b);
|
|||
|
||||
int mtk_parse(uint8_t b, char *gps_rx_buffer);
|
||||
|
||||
int read_gps_mtk(int fd, char *gps_rx_buffer, int buffer_size);
|
||||
int read_gps_mtk(int *fd, char *gps_rx_buffer, int buffer_size);
|
||||
|
||||
int configure_gps_mtk(int fd);
|
||||
int configure_gps_mtk(int *fd);
|
||||
|
||||
void *mtk_loop(void *arg);
|
||||
void *mtk_loop(void *args);
|
||||
|
||||
void *mtk_watchdog_loop(void *arg);
|
||||
void *mtk_watchdog_loop(void *args);
|
||||
|
||||
#endif /* MTK_H_ */
|
||||
|
|
|
@ -34,13 +34,17 @@
|
|||
****************************************************************************/
|
||||
|
||||
/* @file NMEA protocol implementation */
|
||||
|
||||
#include "gps.h"
|
||||
#include "nmea_helper.h"
|
||||
#include <sys/prctl.h>
|
||||
#include <unistd.h>
|
||||
#include <poll.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
#include <arch/board/up_hrt.h>
|
||||
|
||||
#define NMEA_HEALTH_SUCCESS_COUNTER_LIMIT 2
|
||||
#define NMEA_HEALTH_FAIL_COUNTER_LIMIT 2
|
||||
|
@ -59,7 +63,7 @@ extern bool gps_verbose;
|
|||
extern int current_gps_speed;
|
||||
|
||||
|
||||
int read_gps_nmea(int fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info, nmeaPARSER *parser)
|
||||
int read_gps_nmea(int *fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info, nmeaPARSER *parser)
|
||||
{
|
||||
int ret = 1;
|
||||
char c;
|
||||
|
@ -69,7 +73,7 @@ int read_gps_nmea(int fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info,
|
|||
int gpsRxOverflow = 0;
|
||||
|
||||
struct pollfd fds;
|
||||
fds.fd = fd;
|
||||
fds.fd = *fd;
|
||||
fds.events = POLLIN;
|
||||
|
||||
// NMEA or SINGLE-SENTENCE GPS mode
|
||||
|
@ -86,7 +90,7 @@ int read_gps_nmea(int fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info,
|
|||
}
|
||||
|
||||
if (poll(&fds, 1, 1000) > 0) {
|
||||
if (read(fd, &c, 1) > 0) {
|
||||
if (read(*fd, &c, 1) > 0) {
|
||||
// detect start while acquiring stream
|
||||
// printf("Char = %c\n", c);
|
||||
if (!start_flag && (c == '$')) {
|
||||
|
@ -155,13 +159,15 @@ float ndeg2degree(float val)
|
|||
return val;
|
||||
}
|
||||
|
||||
void *nmea_loop(void *arg)
|
||||
void *nmea_loop(void *args)
|
||||
{
|
||||
/* Set thread name */
|
||||
prctl(PR_SET_NAME, "gps nmea read", getpid());
|
||||
|
||||
/* Retrieve file descriptor */
|
||||
int fd = *((int *)arg);
|
||||
/* Retrieve file descriptor and thread flag */
|
||||
struct arg_struct *arguments = (struct arg_struct *)args;
|
||||
int *fd = arguments->fd_ptr;
|
||||
bool *thread_should_exit = arguments->thread_should_exit_ptr;
|
||||
|
||||
/* Initialize gps stuff */
|
||||
nmeaINFO info_d;
|
||||
|
@ -174,11 +180,11 @@ void *nmea_loop(void *arg)
|
|||
nmea_zero_INFO(info);
|
||||
|
||||
/* advertise GPS topic */
|
||||
struct vehicle_gps_position_s nmea_gps_d = {0};
|
||||
struct vehicle_gps_position_s nmea_gps_d = {.counter=0};
|
||||
nmea_gps = &nmea_gps_d;
|
||||
orb_advert_t gps_handle = orb_advertise(ORB_ID(vehicle_gps_position), nmea_gps);
|
||||
|
||||
while (1) {
|
||||
while (!(*thread_should_exit)) {
|
||||
/* Parse a message from the gps receiver */
|
||||
uint8_t read_res = read_gps_nmea(fd, gps_rx_buffer, NMEA_BUFFER_SIZE, info, &parser);
|
||||
|
||||
|
@ -200,11 +206,11 @@ void *nmea_loop(void *arg)
|
|||
// printf("%d.%d.%d %d:%d:%d:%d\n", timeinfo.tm_year, timeinfo.tm_mon, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec, info->utc.hsec);
|
||||
|
||||
nmea_gps->timestamp = hrt_absolute_time();
|
||||
nmea_gps->time_gps_usec = epoch * 1e6 + info->utc.hsec * 1e4;
|
||||
nmea_gps->time_gps_usec = (uint64_t)((epoch)*1000000 + (info->utc.hsec)*10000);
|
||||
nmea_gps->fix_type = (uint8_t)info->fix;
|
||||
nmea_gps->lat = (int32_t)(ndeg2degree(info->lat) * 1e7);
|
||||
nmea_gps->lon = (int32_t)(ndeg2degree(info->lon) * 1e7);
|
||||
nmea_gps->alt = (int32_t)(info->elv * 1e3);
|
||||
nmea_gps->lat = (int32_t)(ndeg2degree(info->lat) * 1e7f);
|
||||
nmea_gps->lon = (int32_t)(ndeg2degree(info->lon) * 1e7f);
|
||||
nmea_gps->alt = (int32_t)(info->elv * 1000.0f);
|
||||
nmea_gps->eph = (uint16_t)(info->HDOP * 100); //TODO:test scaling
|
||||
nmea_gps->epv = (uint16_t)(info->VDOP * 100); //TODO:test scaling
|
||||
nmea_gps->vel = (uint16_t)(info->speed * 1000 / 36); //*1000/3600*100
|
||||
|
@ -251,12 +257,12 @@ void *nmea_loop(void *arg)
|
|||
|
||||
//destroy gps parser
|
||||
nmea_parser_destroy(&parser);
|
||||
|
||||
if(gps_verbose) printf("[gps] nmea loop is going to terminate\n");
|
||||
return NULL;
|
||||
|
||||
}
|
||||
|
||||
void *nmea_watchdog_loop(void *arg)
|
||||
void *nmea_watchdog_loop(void *args)
|
||||
{
|
||||
/* Set thread name */
|
||||
prctl(PR_SET_NAME, "gps nmea watchdog", getpid());
|
||||
|
@ -267,9 +273,14 @@ void *nmea_watchdog_loop(void *arg)
|
|||
uint8_t nmea_success_count = 0;
|
||||
bool once_ok = false;
|
||||
|
||||
/* Retrieve file descriptor and thread flag */
|
||||
struct arg_struct *arguments = (struct arg_struct *)args;
|
||||
//int *fd = arguments->fd_ptr;
|
||||
bool *thread_should_exit = arguments->thread_should_exit_ptr;
|
||||
|
||||
int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
while (1) {
|
||||
while (!(*thread_should_exit)) {
|
||||
// printf("nmea_watchdog_loop : while ");
|
||||
/* if we have no update for a long time print warning (in nmea mode there is no reconfigure) */
|
||||
pthread_mutex_lock(nmea_mutex);
|
||||
|
@ -328,8 +339,7 @@ void *nmea_watchdog_loop(void *arg)
|
|||
|
||||
usleep(NMEA_WATCHDOG_WAIT_TIME_MICROSECONDS);
|
||||
}
|
||||
|
||||
if(gps_verbose) printf("[gps] nmea watchdog loop is going to terminate\n");
|
||||
close(mavlink_fd);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -30,7 +30,7 @@ extern pthread_mutex_t *nmea_mutex;
|
|||
|
||||
|
||||
|
||||
int read_gps_nmea(int fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info, nmeaPARSER *parser);
|
||||
int read_gps_nmea(int *fd, char *gps_rx_buffer, int buffer_size, nmeaINFO *info, nmeaPARSER *parser);
|
||||
|
||||
void *nmea_loop(void *arg);
|
||||
|
||||
|
|
|
@ -35,12 +35,16 @@
|
|||
|
||||
/* @file U-Blox protocol implementation */
|
||||
|
||||
|
||||
#include "ubx.h"
|
||||
#include "gps.h"
|
||||
#include <sys/prctl.h>
|
||||
#include <poll.h>
|
||||
#include <arch/board/up_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
|
@ -340,8 +344,8 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
|
|||
|
||||
|
||||
|
||||
ubx_gps->time_gps_usec = (uint64_t)epoch * 1e6; //TODO: test this
|
||||
ubx_gps->time_gps_usec += packet->time_nanoseconds * 1e-3;
|
||||
ubx_gps->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
|
||||
ubx_gps->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f);
|
||||
|
||||
ubx_gps->timestamp = hrt_absolute_time();
|
||||
ubx_gps->counter++;
|
||||
|
@ -474,7 +478,7 @@ int ubx_parse(uint8_t b, char *gps_rx_buffer)
|
|||
if (ubx_state->ck_a == packet->ck_a && ubx_state->ck_b == packet->ck_b) {
|
||||
|
||||
ubx_gps->vel = (uint16_t)packet->speed;
|
||||
ubx_gps->cog = (uint16_t)((float)(packet->heading) * 1e-3);
|
||||
ubx_gps->cog = (uint16_t)((float)(packet->heading) * 1e-3f);
|
||||
|
||||
ubx_gps->timestamp = hrt_absolute_time();
|
||||
ubx_gps->counter++;
|
||||
|
@ -570,44 +574,44 @@ void calculate_ubx_checksum(uint8_t *message, uint8_t length)
|
|||
// printf("[%x,%x]\n", message[length-2], message[length-1]);
|
||||
}
|
||||
|
||||
int configure_gps_ubx(int fd)
|
||||
int configure_gps_ubx(int *fd)
|
||||
{
|
||||
fflush((FILE *)fd);
|
||||
//fflush(((FILE *)fd));
|
||||
|
||||
//TODO: write this in a loop once it is tested
|
||||
//UBX_CFG_PRT_PART:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_PRT, sizeof(UBX_CONFIG_MESSAGE_PRT) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_PRT, sizeof(UBX_CONFIG_MESSAGE_PRT) / sizeof(uint8_t) , *fd);
|
||||
|
||||
usleep(100000);
|
||||
|
||||
//NAV_POSLLH:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_POSLLH, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_POSLLH) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_POSLLH, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_POSLLH) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
//NAV_TIMEUTC:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_TIMEUTC, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_TIMEUTC) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_TIMEUTC, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_TIMEUTC) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
//NAV_DOP:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_DOP, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_DOP) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_DOP, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_DOP) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
//NAV_SOL:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_SOL, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_SOL) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_SOL, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_SOL) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
|
||||
//NAV_SVINFO:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_SVINFO, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_SVINFO) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_SVINFO, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_SVINFO) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
//NAV_VELNED:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_VELNED, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_VELNED) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_NAV_VELNED, sizeof(UBX_CONFIG_MESSAGE_MSG_NAV_VELNED) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
|
||||
//RXM_SVSI:
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_RXM_SVSI, sizeof(UBX_CONFIG_MESSAGE_MSG_RXM_SVSI) / sizeof(uint8_t) , fd);
|
||||
write_config_message_ubx(UBX_CONFIG_MESSAGE_MSG_RXM_SVSI, sizeof(UBX_CONFIG_MESSAGE_MSG_RXM_SVSI) / sizeof(uint8_t) , *fd);
|
||||
usleep(100000);
|
||||
|
||||
return 0;
|
||||
|
@ -615,16 +619,15 @@ int configure_gps_ubx(int fd)
|
|||
|
||||
|
||||
|
||||
int read_gps_ubx(int fd, char *gps_rx_buffer, int buffer_size)
|
||||
int read_gps_ubx(int *fd, char *gps_rx_buffer, int buffer_size)
|
||||
{
|
||||
|
||||
uint8_t ret = 0;
|
||||
uint8_t c;
|
||||
int rx_count = 0;
|
||||
int gpsRxOverflow = 0;
|
||||
|
||||
struct pollfd fds;
|
||||
fds.fd = fd;
|
||||
fds.fd = *fd;
|
||||
fds.events = POLLIN;
|
||||
|
||||
// UBX GPS mode
|
||||
|
@ -641,7 +644,7 @@ int read_gps_ubx(int fd, char *gps_rx_buffer, int buffer_size)
|
|||
}
|
||||
|
||||
if (poll(&fds, 1, 1000) > 0) {
|
||||
if (read(fd, &c, 1) > 0) {
|
||||
if (read(*fd, &c, 1) > 0) {
|
||||
|
||||
// printf("Read %x\n",c);
|
||||
if (rx_count >= buffer_size) {
|
||||
|
@ -685,7 +688,7 @@ int write_config_message_ubx(uint8_t *message, size_t length, int fd)
|
|||
uint8_t ck_a = 0;
|
||||
uint8_t ck_b = 0;
|
||||
|
||||
int i;
|
||||
unsigned int i;
|
||||
|
||||
for (i = 2; i < length; i++) {
|
||||
ck_a = ck_a + message[i];
|
||||
|
@ -702,14 +705,16 @@ int write_config_message_ubx(uint8_t *message, size_t length, int fd)
|
|||
|
||||
}
|
||||
|
||||
void *ubx_watchdog_loop(void *arg)
|
||||
void *ubx_watchdog_loop(void *args)
|
||||
{
|
||||
/* Set thread name */
|
||||
prctl(PR_SET_NAME, "gps ubx watchdog", getpid());
|
||||
|
||||
|
||||
/* Retrieve file descriptor */
|
||||
int fd = *((int *)arg);
|
||||
/* Retrieve file descriptor and thread flag */
|
||||
struct arg_struct *arguments = (struct arg_struct *)args;
|
||||
int *fd = arguments->fd_ptr;
|
||||
bool *thread_should_exit = arguments->thread_should_exit_ptr;
|
||||
|
||||
/* GPS watchdog error message skip counter */
|
||||
|
||||
|
@ -721,7 +726,9 @@ void *ubx_watchdog_loop(void *arg)
|
|||
|
||||
int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
|
||||
while (1) {
|
||||
//int err_skip_counter = 0;
|
||||
|
||||
while (!(*thread_should_exit)) {
|
||||
/* if some values are to old reconfigure gps */
|
||||
int i;
|
||||
pthread_mutex_lock(ubx_mutex);
|
||||
|
@ -766,7 +773,6 @@ void *ubx_watchdog_loop(void *arg)
|
|||
ubx_healthy = false;
|
||||
ubx_success_count = 0;
|
||||
}
|
||||
|
||||
/* trying to reconfigure the gps configuration */
|
||||
configure_gps_ubx(fd);
|
||||
fflush(stdout);
|
||||
|
@ -777,7 +783,7 @@ void *ubx_watchdog_loop(void *arg)
|
|||
ubx_success_count++;
|
||||
|
||||
if (!ubx_healthy && ubx_success_count == UBX_HEALTH_SUCCESS_COUNTER_LIMIT) {
|
||||
printf("[gps] ublox UBX module status ok (baud=%d)\r\n", current_gps_speed);
|
||||
//printf("[gps] ublox UBX module status ok (baud=%d)\r\n", current_gps_speed);
|
||||
// global_data_send_subsystem_info(&ubx_present_enabled_healthy);
|
||||
mavlink_log_info(mavlink_fd, "[gps] UBX module found, status ok\n");
|
||||
ubx_healthy = true;
|
||||
|
@ -790,18 +796,20 @@ void *ubx_watchdog_loop(void *arg)
|
|||
usleep(UBX_WATCHDOG_WAIT_TIME_MICROSECONDS);
|
||||
}
|
||||
|
||||
if(gps_verbose) printf("[gps] ubx loop is going to terminate\n");
|
||||
close(mavlink_fd);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void *ubx_loop(void *arg)
|
||||
void *ubx_loop(void *args)
|
||||
{
|
||||
/* Set thread name */
|
||||
prctl(PR_SET_NAME, "gps ubx read", getpid());
|
||||
|
||||
/* Retrieve file descriptor */
|
||||
int fd = *((int *)arg);
|
||||
/* Retrieve file descriptor and thread flag */
|
||||
struct arg_struct *arguments = (struct arg_struct *)args;
|
||||
int *fd = arguments->fd_ptr;
|
||||
bool *thread_should_exit = arguments->thread_should_exit_ptr;
|
||||
|
||||
/* Initialize gps stuff */
|
||||
char gps_rx_buffer[UBX_BUFFER_SIZE];
|
||||
|
@ -809,14 +817,13 @@ void *ubx_loop(void *arg)
|
|||
|
||||
if (gps_verbose) printf("[gps] UBX protocol driver starting..\r\n");
|
||||
|
||||
//set parameters for ubx
|
||||
//set parameters for ubx_state
|
||||
|
||||
|
||||
// //ubx state
|
||||
// gps_bin_ubx_state_t * ubx_state = malloc(sizeof(gps_bin_ubx_state_t));
|
||||
//ubx state
|
||||
ubx_state = malloc(sizeof(gps_bin_ubx_state_t));
|
||||
//printf("gps: ubx_state created\n");
|
||||
// ubx_decode_init();
|
||||
// ubx_state->print_errors = false;
|
||||
ubx_decode_init();
|
||||
ubx_state->print_errors = false;
|
||||
|
||||
|
||||
/* set parameters for ubx */
|
||||
|
@ -825,7 +832,7 @@ void *ubx_loop(void *arg)
|
|||
printf("[gps] Configuration of gps module to ubx failed\r\n");
|
||||
|
||||
/* Write shared variable sys_status */
|
||||
|
||||
// TODO enable this again
|
||||
//global_data_send_subsystem_info(&ubx_present);
|
||||
|
||||
} else {
|
||||
|
@ -834,17 +841,17 @@ void *ubx_loop(void *arg)
|
|||
// XXX Shouldn't the system status only change if the module is known to work ok?
|
||||
|
||||
/* Write shared variable sys_status */
|
||||
|
||||
// TODO enable this again
|
||||
//global_data_send_subsystem_info(&ubx_present_enabled);
|
||||
}
|
||||
|
||||
struct vehicle_gps_position_s ubx_gps_d = {0};
|
||||
struct vehicle_gps_position_s ubx_gps_d = {.counter = 0};
|
||||
|
||||
ubx_gps = &ubx_gps_d;
|
||||
|
||||
orb_advert_t gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &ubx_gps);
|
||||
|
||||
while (1) {
|
||||
while (!(*thread_should_exit)) {
|
||||
/* Parse a message from the gps receiver */
|
||||
if (0 == read_gps_ubx(fd, gps_rx_buffer, UBX_BUFFER_SIZE)) {
|
||||
/* publish new GPS position */
|
||||
|
@ -857,7 +864,8 @@ void *ubx_loop(void *arg)
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
if(gps_verbose) printf("[gps] ubx read is going to terminate\n");
|
||||
close(gps_pub);
|
||||
return NULL;
|
||||
|
||||
}
|
||||
|
|
|
@ -298,17 +298,17 @@ void ubx_checksum(uint8_t b, uint8_t *ck_a, uint8_t *ck_b);
|
|||
|
||||
int ubx_parse(uint8_t b, char *gps_rx_buffer);
|
||||
|
||||
int configure_gps_ubx(int fd);
|
||||
int configure_gps_ubx(int *fd);
|
||||
|
||||
int read_gps_ubx(int fd, char *gps_rx_buffer, int buffer_size);
|
||||
int read_gps_ubx(int *fd, char *gps_rx_buffer, int buffer_size);
|
||||
|
||||
int write_config_message_ubx(uint8_t *message, size_t length, int fd);
|
||||
|
||||
void calculate_ubx_checksum(uint8_t *message, uint8_t length);
|
||||
|
||||
void *ubx_watchdog_loop(void *arg);
|
||||
void *ubx_watchdog_loop(void *args);
|
||||
|
||||
void *ubx_loop(void *arg);
|
||||
void *ubx_loop(void *args);
|
||||
|
||||
|
||||
#endif /* UBX_H_ */
|
||||
|
|
|
@ -234,9 +234,11 @@
|
|||
#endif
|
||||
|
||||
/* This is the maximum number of arguments that will be accepted for a command */
|
||||
|
||||
#define NSH_MAX_ARGUMENTS 6
|
||||
|
||||
#ifdef CONFIG_NSH_MAX_ARGUMENTS
|
||||
# define NSH_MAX_ARGUMENTS CONFIG_NSH_MAX_ARGUMENTS
|
||||
#else
|
||||
# define NSH_MAX_ARGUMENTS 10
|
||||
#endif
|
||||
/* strerror() produces much nicer output but is, however, quite large and
|
||||
* will only be used if CONFIG_NSH_STRERROR is defined. Note that the strerror
|
||||
* interface must also have been enabled with CONFIG_LIBC_STRERROR.
|
||||
|
|
|
@ -68,3 +68,4 @@ distclean: clean
|
|||
@for dir in $(INSTALLED_DIRS) ; do \
|
||||
$(MAKE) -C $$dir distclean TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"; \
|
||||
done
|
||||
|
||||
|
|
|
@ -1458,7 +1458,7 @@
|
|||
* Renamed arc/hc/include/mc9s12ne64 and src/mc9s12ne64 to m9s12. That name is
|
||||
shorter and more general.
|
||||
* The NuttX repository has been converted to SVN and can now be found here
|
||||
http://nuttx.svn.sourceforge.net/viewvc/nuttx/
|
||||
http://svn.code.sf.net/p/nuttx/code/trunk/
|
||||
* configs/mbed/hidkbd: Added USB host support for the mbed LPC1768 board; add
|
||||
a USB host HID keyboard configuraion.
|
||||
* drivers/usbhost/hid_parser.c: Leverages the LUFA HID parser written by
|
||||
|
@ -3367,4 +3367,13 @@
|
|||
this header file.
|
||||
* drivers/mtd/w25.c: The Windbond SPI FLASH W25 FLASH driver is
|
||||
code complete (but still untested).
|
||||
|
||||
* arch/arm/src/stm32/stm32_i2c.c: I2C improvements from Mike Smith.
|
||||
Unified configuration logic; dynamic timeout calculations;
|
||||
I2C reset logic to recover from locked devices on the bus.
|
||||
* configs/*/*/Make.defs, tools/Config.mk, Makefile: Refactor all
|
||||
common make definitions from the various Make.defs files into
|
||||
the common tools/Make.mk. Add support for a verbosity options:
|
||||
Specify V=1 on the make command line in order to see the exact
|
||||
commands used in the build (Contributed by Richard Cochran).
|
||||
* drivers/net/enc28j60.c: The ENC28J60 Ethernet driver is
|
||||
now functional.
|
||||
|
|
|
@ -38,6 +38,13 @@ TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'}
|
|||
-include ${TOPDIR}/tools/Config.mk
|
||||
-include ${TOPDIR}/Make.defs
|
||||
|
||||
# Control build verbosity.
|
||||
ifeq ($(V),1)
|
||||
export Q :=
|
||||
else
|
||||
export Q := @
|
||||
endif
|
||||
|
||||
# Default tools
|
||||
|
||||
ifeq ($(DIRLINK),)
|
||||
|
|
|
@ -17,7 +17,7 @@ README
|
|||
o Building NuttX
|
||||
- Building
|
||||
- Re-building
|
||||
- Build Targets
|
||||
- Build Targets and Options
|
||||
o Cygwin Build Problems
|
||||
- Strange Path Problems
|
||||
- Window Native Toolchain Issues
|
||||
|
@ -118,7 +118,7 @@ Installation Directories with Spaces in the Path
|
|||
I work around spaces in the home directory name, by creating a
|
||||
new directory that does not contain any spaces, such as /home/nuttx.
|
||||
Then I install NuttX in /home/nuttx and always build from
|
||||
/home/nuttx/nuttx.
|
||||
/home/nuttx/nuttx-code.
|
||||
|
||||
Notes about Header Files
|
||||
------------------------
|
||||
|
@ -380,9 +380,10 @@ Re-building
|
|||
This 'make' command will remove of the copied directories, re-copy them,
|
||||
then make NuttX.
|
||||
|
||||
Build Targets
|
||||
-------------
|
||||
Build Targets and Options
|
||||
-------------------------
|
||||
|
||||
Build Targets:
|
||||
Below is a summary of the build targets available in the top-level
|
||||
NuttX Makefile:
|
||||
|
||||
|
@ -455,6 +456,18 @@ Build Targets
|
|||
This is part of the distclean target. It removes all of the header files
|
||||
and symbolic links created by the context target.
|
||||
|
||||
Build Options:
|
||||
Of course, the value any make variable an be overriden from the make command
|
||||
line. However, there is one particular variable assignment option that may
|
||||
be useful to you:
|
||||
|
||||
V=1
|
||||
|
||||
This is the build "verbosity flag." If you specify V=1 on the make command
|
||||
line, you will see the exact commands used in the build. This can be very
|
||||
useful when adding new boards or tracking down compile time errors and
|
||||
warnings (Contributed by Richard Cochran).
|
||||
|
||||
CYGWIN BUILD PROBLEMS
|
||||
^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
|
|
|
@ -1968,7 +1968,7 @@ release includes several new features:
|
|||
small for the MCU usage and has some limitations. No formal
|
||||
documentation of NXFFS yet exists. See the fs/nxffs/README.txt
|
||||
file for details (see
|
||||
http://nuttx.svn.sourceforge.net/viewvc/nuttx/trunk/nuttx/fs/nxffs/README.txt?view=log)
|
||||
http://svn.code.sf.net/p/nuttx/code/trunk/nuttx/fs/nxffs/README.txt?view=log)
|
||||
* Support for NXP LPCXpresso LPC1768 board on the Embedded
|
||||
Artists base board. The Code Red toolchain is supported under
|
||||
either Linux or Windows. Verified configurations include
|
||||
|
|
|
@ -103,6 +103,7 @@ config ARCH_CHIP_STM32
|
|||
bool "STMicro STM32"
|
||||
select ARCH_HAVE_CMNVECTOR
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_HAVE_I2CRESET
|
||||
---help---
|
||||
STMicro STM32 architectures (ARM Cortex-M3/4).
|
||||
|
||||
|
|
|
@ -191,14 +191,17 @@ menu "STM32 Peripheral Support"
|
|||
config STM32_ADC1
|
||||
bool "ADC1"
|
||||
default n
|
||||
select STM32_ADC
|
||||
|
||||
config STM32_ADC2
|
||||
bool "ADC2"
|
||||
default n
|
||||
select STM32_ADC
|
||||
|
||||
config STM32_ADC3
|
||||
bool "ADC3"
|
||||
default n
|
||||
select STM32_ADC
|
||||
|
||||
config STM32_CRC
|
||||
bool "CRC"
|
||||
|
@ -228,12 +231,14 @@ config STM32_CAN1
|
|||
bool "CAN1"
|
||||
default n
|
||||
select CAN
|
||||
select STM32_CAN
|
||||
|
||||
config STM32_CAN2
|
||||
bool "CAN2"
|
||||
default n
|
||||
depends on STM32_STM32F20XX || STM32_STM32F40XX
|
||||
select CAN
|
||||
select STM32_CAN
|
||||
|
||||
config STM32_CCMDATARAM
|
||||
bool "CMD/DATA RAM"
|
||||
|
@ -248,10 +253,12 @@ config STM32_CRYP
|
|||
config STM32_DAC1
|
||||
bool "DAC1"
|
||||
default n
|
||||
select STM32_DAC
|
||||
|
||||
config STM32_DAC2
|
||||
bool "DAC2"
|
||||
default n
|
||||
select STM32_DAC
|
||||
|
||||
config STM32_DCMI
|
||||
bool "DCMI"
|
||||
|
@ -276,15 +283,18 @@ config STM32_HASH
|
|||
config STM32_I2C1
|
||||
bool "I2C1"
|
||||
default n
|
||||
select STM32_I2C
|
||||
|
||||
config STM32_I2C2
|
||||
bool "I2C2"
|
||||
default n
|
||||
select STM32_I2C
|
||||
|
||||
config STM32_I2C3
|
||||
bool "I2C3"
|
||||
default n
|
||||
depends on STM32_STM32F20XX || STM32_STM32F40XX
|
||||
select STM32_I2C
|
||||
|
||||
config STM32_IWDG
|
||||
bool "IWDG"
|
||||
|
@ -319,23 +329,27 @@ config STM32_SPI1
|
|||
bool "SPI1"
|
||||
default n
|
||||
select SPI
|
||||
select STM32_SPI
|
||||
|
||||
config STM32_SPI2
|
||||
bool "SPI2"
|
||||
default n
|
||||
select SPI
|
||||
select STM32_SPI
|
||||
|
||||
config STM32_SPI3
|
||||
bool "SPI3"
|
||||
default n
|
||||
depends on STM32_STM32F20XX || STM32_STM32F40XX
|
||||
select SPI
|
||||
select STM32_SPI
|
||||
|
||||
config STM32_SPI4
|
||||
bool "SPI4"
|
||||
default n
|
||||
depends on STM32_STM32F10XX
|
||||
select SPI
|
||||
select STM32_SPI
|
||||
|
||||
config STM32_SYSCFG
|
||||
bool "SYSCFG"
|
||||
|
@ -450,19 +464,18 @@ endmenu
|
|||
|
||||
config STM32_ADC
|
||||
bool
|
||||
default y if STM32_ADC1 || STM32_ADC2 || STM32_ADC3
|
||||
|
||||
config STM32_DAC
|
||||
bool
|
||||
default y if STM32_DAC1 || STM32_ADC2
|
||||
|
||||
config STM32_SPI
|
||||
bool
|
||||
default y if STM32_SPI1 || STM32_SPI2 || STM32_SPI3 || STM32_SPI4
|
||||
|
||||
config STM32_I2C
|
||||
bool
|
||||
|
||||
config STM32_CAN
|
||||
bool
|
||||
default y if STM32_CAN1 || STM32_CAN2
|
||||
|
||||
menu "Alternate Pin Mapping"
|
||||
|
||||
|
@ -571,10 +584,10 @@ choice
|
|||
config STM32_CAN1_NO_REMAP
|
||||
bool "No pin remapping"
|
||||
|
||||
config CONFIG_STM32_CAN1_REMAP1
|
||||
config STM32_CAN1_REMAP1
|
||||
bool "CAN1 alternate pin remapping #1"
|
||||
|
||||
config CONFIG_STM32_CAN1_REMAP2
|
||||
config STM32_CAN1_REMAP2
|
||||
bool "CAN1 alternate pin remapping #2"
|
||||
|
||||
endchoice
|
||||
|
@ -1600,6 +1613,46 @@ config STM32_SPI_DMA
|
|||
|
||||
endmenu
|
||||
|
||||
menu "I2C Configuration"
|
||||
depends on STM32_I2C
|
||||
|
||||
config STM32_I2C_DYNTIMEO
|
||||
bool "Use dynamic timeouts"
|
||||
default n
|
||||
depends on STM32_I2C
|
||||
|
||||
config STM32_I2C_DYNTIMEO_USECPERBYTE
|
||||
int "Timeout Microseconds per Byte"
|
||||
default 0
|
||||
depends on STM32_I2C_DYNTIMEO
|
||||
|
||||
config STM32_I2C_DYNTIMEO_STARTSTOP
|
||||
int "Timeout for Start/Stop (Milliseconds)"
|
||||
default 5000
|
||||
depends on STM32_I2C_DYNTIMEO
|
||||
|
||||
config STM32_I2CTIMEOSEC
|
||||
int "Timeout seconds"
|
||||
default 0
|
||||
depends on STM32_I2C
|
||||
|
||||
config STM32_I2CTIMEOMS
|
||||
int "Timeout Milliseconds"
|
||||
default 500
|
||||
depends on STM32_I2C && !STM32_I2C_DYNTIMEO
|
||||
|
||||
config STM32_I2CTIMEOTICKS
|
||||
int "Timeout for Done and Stop (ticks)"
|
||||
default 500
|
||||
depends on STM32_I2C && !STM32_I2C_DYNTIMEO
|
||||
|
||||
config STM32_I2C_DUTY16_9
|
||||
bool "Frequency with Tlow/Thigh = 16/9 "
|
||||
default n
|
||||
depends on STM32_I2C
|
||||
|
||||
endmenu
|
||||
|
||||
menu "SDIO Configuration"
|
||||
depends on STM32_SDIO
|
||||
|
||||
|
@ -1826,13 +1879,13 @@ config STM32_USBHOST_REGDEBUG
|
|||
default n
|
||||
depends on USBHOST && STM32_OTGFS
|
||||
---help---
|
||||
Enable very low-level register access debug. Depends on CONFIG_DEBUG.
|
||||
Enable very low-level register access debug. Depends on DEBUG.
|
||||
|
||||
config STM32_USBHOST_PKTDUMP
|
||||
bool "Packet Dump Debug"
|
||||
default n
|
||||
depends on USBHOST && STM32_OTGFS
|
||||
---help---
|
||||
Dump all incoming and outgoing USB packets. Depends on CONFIG_DEBUG.
|
||||
Dump all incoming and outgoing USB packets. Depends on DEBUG.
|
||||
|
||||
endmenu
|
||||
|
|
|
@ -1805,7 +1805,7 @@ configs/z16f2800100zcog
|
|||
configs/z80sim
|
||||
z80 Microcontroller. This port uses a Z80 instruction set simulator.
|
||||
That simulator can be found in the NuttX SVN at
|
||||
http://nuttx.svn.sourceforge.net/viewvc/nuttx/trunk/misc/sims/z80sim.
|
||||
http://svn.code.sf.net/p/nuttx/code/trunk/misc/sims/z80sim.
|
||||
This port also uses the SDCC toolchain (http://sdcc.sourceforge.net/")
|
||||
(verified with version 2.6.0).
|
||||
|
||||
|
|
|
@ -941,6 +941,7 @@ CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6"
|
|||
# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
|
||||
# CONFIG_NSH_STRERROR - Use strerror(errno)
|
||||
# CONFIG_NSH_LINELEN - Maximum length of one command line
|
||||
# CONFIG_NSH_MAX_ARGUMENTS - Maximum number of arguments for command line
|
||||
# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
|
||||
# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
|
||||
# CONFIG_NSH_DISABLEBG - Disable background commands
|
||||
|
@ -972,6 +973,7 @@ CONFIG_NSH_BUILTIN_APPS=y
|
|||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAX_ARGUMENTS=12
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_DISABLESCRIPT=n
|
||||
CONFIG_NSH_DISABLEBG=n
|
||||
|
|
|
@ -119,6 +119,14 @@ config I2C_NTRACE
|
|||
default n
|
||||
depends on I2C_TRACE
|
||||
|
||||
config ARCH_HAVE_I2CRESET
|
||||
bool
|
||||
|
||||
config I2C_RESET
|
||||
bool "Support up_i2creset"
|
||||
default n
|
||||
depends on I2C && ARCH_HAVE_I2CRESET
|
||||
|
||||
menuconfig SPI
|
||||
bool "SPI Driver Support"
|
||||
default n
|
||||
|
|
|
@ -70,6 +70,13 @@ config ENC28J60_DUMPPACKET
|
|||
If selected, the ENC28J60 driver will dump the contents of each
|
||||
packet to the console.
|
||||
|
||||
config ENC28J60_REGDEBUG
|
||||
bool "Register-Level Debug"
|
||||
default n
|
||||
depends on DEBUG && DEBUG_NET
|
||||
---help---
|
||||
Enable very low-level register access debug. Depends on DEBUG and DEBUG_NET.
|
||||
|
||||
endif
|
||||
|
||||
config NET_E1000
|
||||
|
|
|
@ -42,6 +42,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#if defined(CONFIG_NET) && defined(CONFIG_ENC28J60)
|
||||
|
||||
#include <stdint.h>
|
||||
|
@ -128,6 +129,12 @@
|
|||
# warrning "CONFIG_NET_NOINTS should be set"
|
||||
#endif
|
||||
|
||||
/* Low-level register debug */
|
||||
|
||||
#if !defined(CONFIG_DEBUG) || !defined(CONFIG_DEBUG_NET)
|
||||
# undef CONFIG_ENC28J60_REGDEBUG
|
||||
#endif
|
||||
|
||||
/* Timing *******************************************************************/
|
||||
|
||||
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
|
||||
|
@ -169,6 +176,20 @@
|
|||
|
||||
#define BUF ((struct uip_eth_hdr *)priv->dev.d_buf)
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_ENC28J60_REGDEBUG
|
||||
# define enc_wrdump(a,v) lib_lowprintf("ENC28J60: %02x<-%02x\n", a, v);
|
||||
# define enc_rddump(a,v) lib_lowprintf("ENC28J60: %02x->%02x\n", a, v);
|
||||
# define enc_cmddump(c) lib_lowprintf("ENC28J60: CMD: %02x\n", c);
|
||||
# define enc_bmdump(c,b,s) lib_lowprintf("ENC28J60: CMD: %02x buffer: %p length: %d\n", c,b,s);
|
||||
#else
|
||||
# define enc_wrdump(a,v)
|
||||
# define enc_rddump(a,v)
|
||||
# define enc_cmddump(c)
|
||||
# define enc_bmdump(c,b,s)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
@ -192,9 +213,6 @@ struct enc_driver_s
|
|||
|
||||
uint8_t ifstate; /* Interface state: See ENCSTATE_* */
|
||||
uint8_t bank; /* Currently selected bank */
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
uint8_t lockcount; /* Avoid recursive locks */
|
||||
#endif
|
||||
uint16_t nextpkt; /* Next packet address */
|
||||
FAR const struct enc_lower_s *lower; /* Low-level MCU-specific support */
|
||||
|
||||
|
@ -238,13 +256,14 @@ static struct enc_driver_s g_enc28j60[CONFIG_ENC28J60_NINTERFACES];
|
|||
|
||||
/* Low-level SPI helpers */
|
||||
|
||||
static inline void enc_configspi(FAR struct spi_dev_s *spi);
|
||||
#ifdef CONFIG_SPI_OWNBUS
|
||||
static inline void enc_select(FAR struct enc_driver_s *priv);
|
||||
static inline void enc_deselect(FAR struct enc_driver_s *priv);
|
||||
static inline void enc_configspi(FAR struct spi_dev_s *spi);
|
||||
# define enc_lock(priv);
|
||||
# define enc_unlock(priv);
|
||||
#else
|
||||
static void enc_select(FAR struct enc_driver_s *priv);
|
||||
static void enc_deselect(FAR struct enc_driver_s *priv);
|
||||
# define enc_configspi(spi)
|
||||
static void enc_lock(FAR struct enc_driver_s *priv);
|
||||
static inline void enc_unlock(FAR struct enc_driver_s *priv);
|
||||
#endif
|
||||
|
||||
/* SPI control register access */
|
||||
|
@ -260,11 +279,16 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
|
|||
static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
|
||||
uint8_t bits, uint8_t value);
|
||||
|
||||
#if 0 /* Sometimes useful */
|
||||
static void enc_rxdump(FAR struct enc_driver_s *priv);
|
||||
static void enc_txdump(FAR struct enc_driver_s *priv);
|
||||
#endif
|
||||
|
||||
/* SPI buffer transfers */
|
||||
|
||||
static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
|
||||
size_t buflen);
|
||||
static void enc_wrbuffer(FAR struct enc_driver_s *priv,
|
||||
static inline void enc_wrbuffer(FAR struct enc_driver_s *priv,
|
||||
FAR const uint8_t *buffer, size_t buflen);
|
||||
|
||||
/* PHY register access */
|
||||
|
@ -334,23 +358,21 @@ static int enc_reset(FAR struct enc_driver_s *priv);
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SPI_OWNBUS
|
||||
static inline void enc_configspi(FAR struct spi_dev_s *spi)
|
||||
{
|
||||
/* Configure SPI for the ENC28J60. But only if we own the SPI bus.
|
||||
* Otherwise, don't bother because it might change.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SPI_OWNBUS
|
||||
SPI_SETMODE(spi, CONFIG_ENC28J60_SPIMODE);
|
||||
SPI_SETBITS(spi, 8);
|
||||
#ifdef CONFIG_ENC28J60_FREQUENCY
|
||||
SPI_SETFREQUENCY(spi, CONFIG_ENC28J60_FREQUENCY)
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Function: enc_select
|
||||
* Function: enc_lock
|
||||
*
|
||||
* Description:
|
||||
* Select the SPI, locking and re-configuring if necessary
|
||||
|
@ -365,36 +387,14 @@ static inline void enc_configspi(FAR struct spi_dev_s *spi)
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SPI_OWNBUS
|
||||
static inline void enc_select(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
/* We own the SPI bus, so just select the chip */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);
|
||||
}
|
||||
#else
|
||||
static void enc_select(FAR struct enc_driver_s *priv)
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
static void enc_lock(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
/* Lock the SPI bus in case there are multiple devices competing for the SPI
|
||||
* bus. First check if we already hold the lock.
|
||||
* bus.
|
||||
*/
|
||||
|
||||
if (priv->lockcount > 0)
|
||||
{
|
||||
/* Yes... just increment the lock count. In this case, we know
|
||||
* that the bus has already been configured for the ENC28J60.
|
||||
*/
|
||||
|
||||
DEBUGASSERT(priv->lockcount < 255);
|
||||
priv->lockcount++;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* No... take the lock and set the lock count to 1 */
|
||||
|
||||
DEBUGASSERT(priv->lockcount == 0);
|
||||
SPI_LOCK(priv->spi, true);
|
||||
priv->lockcount = 1;
|
||||
|
||||
/* Now make sure that the SPI bus is configured for the ENC28J60 (it
|
||||
* might have gotten configured for a different device while unlocked)
|
||||
|
@ -402,19 +402,12 @@ static void enc_select(FAR struct enc_driver_s *priv)
|
|||
|
||||
SPI_SETMODE(priv->spi, CONFIG_ENC28J60_SPIMODE);
|
||||
SPI_SETBITS(priv->spi, 8);
|
||||
#ifdef CONFIG_ENC28J60_FREQUENCY
|
||||
SPI_SETFREQUENCY(priv->spi, CONFIG_ENC28J60_FREQUENCY);
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Select ENC28J60 chip. */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Function: enc_deselect
|
||||
* Function: enc_unlock
|
||||
*
|
||||
* Description:
|
||||
* De-select the SPI
|
||||
|
@ -429,34 +422,12 @@ static void enc_select(FAR struct enc_driver_s *priv)
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SPI_OWNBUS
|
||||
static inline void enc_deselect(FAR struct enc_driver_s *priv)
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
static inline void enc_unlock(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
/* We own the SPI bus, so just de-select the chip */
|
||||
/* Relinquish the lock on the bus. */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
}
|
||||
#else
|
||||
static void enc_deselect(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
/* De-select ENC28J60 chip. */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
|
||||
/* And relinquishthe lock on the bus. If the lock count is > 1 then we
|
||||
* are in a nested lock and we only need to decrement the lock cound.
|
||||
*/
|
||||
|
||||
if (priv->lockcount <= 1)
|
||||
{
|
||||
DEBUGASSERT(priv->lockcount == 1);
|
||||
SPI_LOCK(priv->spi, false);
|
||||
priv->lockcount = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
priv->lockcount--;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -486,7 +457,7 @@ static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd)
|
|||
|
||||
/* Select ENC28J60 chip */
|
||||
|
||||
enc_select(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the read command and collect the data. The sequence requires
|
||||
* 16-clocks: 8 to clock out the cmd + 8 to clock in the data.
|
||||
|
@ -497,7 +468,9 @@ static uint8_t enc_rdgreg2(FAR struct enc_driver_s *priv, uint8_t cmd)
|
|||
|
||||
/* De-select ENC28J60 chip */
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
|
||||
enc_rddump(cmd, rddata);
|
||||
return rddata;
|
||||
}
|
||||
|
||||
|
@ -527,7 +500,7 @@ static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd,
|
|||
|
||||
/* Select ENC28J60 chip */
|
||||
|
||||
enc_select(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the write command and data. The sequence requires 16-clocks:
|
||||
* 8 to clock out the cmd + 8 to clock out the data.
|
||||
|
@ -538,7 +511,8 @@ static void enc_wrgreg2(FAR struct enc_driver_s *priv, uint8_t cmd,
|
|||
|
||||
/* De-select ENC28J60 chip. */
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
enc_wrdump(cmd, wrdata);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -570,7 +544,7 @@ static inline void enc_src(FAR struct enc_driver_s *priv)
|
|||
|
||||
/* Select ENC28J60 chip */
|
||||
|
||||
enc_select(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the system reset command. */
|
||||
|
||||
|
@ -591,7 +565,8 @@ static inline void enc_src(FAR struct enc_driver_s *priv)
|
|||
|
||||
/* De-select ENC28J60 chip. */
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
enc_cmddump(ENC_SRC);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -664,9 +639,9 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
|
|||
|
||||
enc_setbank(priv, GETBANK(ctrlreg));
|
||||
|
||||
/* Select ENC28J60 chip */
|
||||
/* Re-select ENC28J60 chip */
|
||||
|
||||
enc_select(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the RCR command and collect the data. How we collect the data
|
||||
* depends on if this is a PHY/CAN or not. The normal sequence requires
|
||||
|
@ -687,7 +662,8 @@ static uint8_t enc_rdbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg)
|
|||
|
||||
/* De-select ENC28J60 chip */
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
enc_rddump(ENC_RCR | GETADDR(ctrlreg), rddata);
|
||||
return rddata;
|
||||
}
|
||||
|
||||
|
@ -716,14 +692,14 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
|
|||
{
|
||||
DEBUGASSERT(priv && priv->spi);
|
||||
|
||||
/* Select ENC28J60 chip */
|
||||
|
||||
enc_select(priv);
|
||||
|
||||
/* Set the bank */
|
||||
|
||||
enc_setbank(priv, GETBANK(ctrlreg));
|
||||
|
||||
/* Re-select ENC28J60 chip */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the WCR command and data. The sequence requires 16-clocks:
|
||||
* 8 to clock out the cmd + 8 to clock out the data.
|
||||
*/
|
||||
|
@ -733,7 +709,8 @@ static void enc_wrbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
|
|||
|
||||
/* De-select ENC28J60 chip. */
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
enc_wrdump(ENC_WCR | GETADDR(ctrlreg), wrdata);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -777,6 +754,78 @@ static int enc_waitbreg(FAR struct enc_driver_s *priv, uint8_t ctrlreg,
|
|||
return (rddata & bits) == value ? -ETIMEDOUT : OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Function: enc_txdump enc_rxdump
|
||||
*
|
||||
* Description:
|
||||
* Dump registers associated with receiving or sending packets.
|
||||
*
|
||||
* Parameters:
|
||||
* priv - Reference to the driver state structure
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#if 0 /* Sometimes useful */
|
||||
static void enc_rxdump(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
lib_lowprintf("Rx Registers:\n");
|
||||
lib_lowprintf(" EIE: %02x EIR: %02x\n",
|
||||
enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR));
|
||||
lib_lowprintf(" ESTAT: %02x ECON1: %02x ECON2: %02x\n",
|
||||
enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1),
|
||||
enc_rdgreg(priv, ENC_ECON2));
|
||||
lib_lowprintf(" ERXST: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_ERXSTH), enc_rdbreg(priv, ENC_ERXSTL));
|
||||
lib_lowprintf(" ERXND: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_ERXNDH), enc_rdbreg(priv, ENC_ERXNDL));
|
||||
lib_lowprintf(" ERXRDPT: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_ERXRDPTH), enc_rdbreg(priv, ENC_ERXRDPTL));
|
||||
lib_lowprintf(" ERXFCON: %02x EPKTCNT: %02x\n",
|
||||
enc_rdbreg(priv, ENC_ERXFCON), enc_rdbreg(priv, ENC_EPKTCNT));
|
||||
lib_lowprintf(" MACON1: %02x MACON3: %02x\n",
|
||||
enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3));
|
||||
lib_lowprintf(" MAMXFL: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
|
||||
lib_lowprintf(" MAADR: %02x:%02x:%02x:%02x:%02x:%02x\n",
|
||||
enc_rdbreg(priv, ENC_MAADR1), enc_rdbreg(priv, ENC_MAADR2),
|
||||
enc_rdbreg(priv, ENC_MAADR3), enc_rdbreg(priv, ENC_MAADR4),
|
||||
enc_rdbreg(priv, ENC_MAADR5), enc_rdbreg(priv, ENC_MAADR6));
|
||||
}
|
||||
#endif
|
||||
|
||||
#if 0 /* Sometimes useful */
|
||||
static void enc_txdump(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
lib_lowprintf("Tx Registers:\n");
|
||||
lib_lowprintf(" EIE: %02x EIR: %02x ESTAT: %02x\n",
|
||||
enc_rdgreg(priv, ENC_EIE), enc_rdgreg(priv, ENC_EIR),);
|
||||
lib_lowprintf(" ESTAT: %02x ECON1: %02x\n",
|
||||
enc_rdgreg(priv, ENC_ESTAT), enc_rdgreg(priv, ENC_ECON1));
|
||||
lib_lowprintf(" ETXST: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_ETXSTH), enc_rdbreg(priv, ENC_ETXSTL));
|
||||
lib_lowprintf(" ETXND: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_ETXNDH), enc_rdbreg(priv, ENC_ETXNDL));
|
||||
lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
|
||||
enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
|
||||
enc_rdbreg(priv, ENC_MACON4));
|
||||
lib_lowprintf(" MACON1: %02x MACON3: %02x MACON4: %02x\n",
|
||||
enc_rdbreg(priv, ENC_MACON1), enc_rdbreg(priv, ENC_MACON3),
|
||||
enc_rdbreg(priv, ENC_MACON4));
|
||||
lib_lowprintf(" MABBIPG: %02x MAIPG %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_MABBIPG), enc_rdbreg(priv, ENC_MAIPGH),
|
||||
enc_rdbreg(priv, ENC_MAIPGL));
|
||||
lib_lowprintf(" MACLCON1: %02x MACLCON2: %02x\n",
|
||||
enc_rdbreg(priv, ENC_MACLCON1), enc_rdbreg(priv, ENC_MACLCON2));
|
||||
lib_lowprintf(" MAMXFL: %02x %02x\n",
|
||||
enc_rdbreg(priv, ENC_MAMXFLH), enc_rdbreg(priv, ENC_MAMXFLL));
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Function: enc_rdbuffer
|
||||
*
|
||||
|
@ -803,7 +852,7 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
|
|||
|
||||
/* Select ENC28J60 chip */
|
||||
|
||||
enc_select(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the read buffer memory command (ignoring the response) */
|
||||
|
||||
|
@ -815,7 +864,8 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
|
|||
|
||||
/* De-select ENC28J60 chip. */
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
enc_bmdump(ENC_WBM, buffer, buflen);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -837,26 +887,68 @@ static void enc_rdbuffer(FAR struct enc_driver_s *priv, FAR uint8_t *buffer,
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void enc_wrbuffer(FAR struct enc_driver_s *priv,
|
||||
static inline void enc_wrbuffer(FAR struct enc_driver_s *priv,
|
||||
FAR const uint8_t *buffer, size_t buflen)
|
||||
{
|
||||
DEBUGASSERT(priv && priv->spi);
|
||||
|
||||
/* Select ENC28J60 chip */
|
||||
/* Select ENC28J60 chip
|
||||
*
|
||||
* "The WBM command is started by lowering the CS pin. ..."
|
||||
*/
|
||||
|
||||
enc_select(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, true);;
|
||||
|
||||
/* Send the write buffer memory command (ignoring the response) */
|
||||
/* Send the write buffer memory command (ignoring the response)
|
||||
*
|
||||
* "...The [3-bit]WBM opcode should then be sent to the ENC28J60,
|
||||
* followed by the 5-bit constant, 1Ah."
|
||||
*/
|
||||
|
||||
(void)SPI_SEND(priv->spi, ENC_WBM);
|
||||
|
||||
/* Then send the buffer */
|
||||
/* "...the ENC28J60 requires a single per packet control byte to
|
||||
* precede the packet for transmission."
|
||||
*
|
||||
* POVERRIDE: Per Packet Override bit (Not set):
|
||||
* 1 = The values of PCRCEN, PPADEN and PHUGEEN will override the
|
||||
* configuration defined by MACON3.
|
||||
* 0 = The values in MACON3 will be used to determine how the packet
|
||||
* will be transmitted
|
||||
* PCRCEN: Per Packet CRC Enable bit (Set, but won't be used because
|
||||
* POVERRIDE is zero).
|
||||
* PPADEN: Per Packet Padding Enable bit (Set, but won't be used because
|
||||
* POVERRIDE is zero).
|
||||
* PHUGEEN: Per Packet Huge Frame Enable bit (Set, but won't be used
|
||||
* because POVERRIDE is zero).
|
||||
*/
|
||||
|
||||
(void)SPI_SEND(priv->spi,
|
||||
(PKTCTRL_PCRCEN | PKTCTRL_PPADEN | PKTCTRL_PHUGEEN));
|
||||
|
||||
/* Then send the buffer
|
||||
*
|
||||
* "... After the WBM command and constant are sent, the data to
|
||||
* be stored in the memory pointed to by EWRPT should be shifted
|
||||
* out MSb first to the ENC28J60. After 8 data bits are received,
|
||||
* the Write Pointer will automatically increment if AUTOINC is
|
||||
* set. The host controller can continue to provide clocks on the
|
||||
* SCK pin and send data on the SI pin, without raising CS, to
|
||||
* keep writing to the memory. In this manner, with AUTOINC
|
||||
* enabled, it is possible to continuously write sequential bytes
|
||||
* to the buffer memory without any extra SPI command
|
||||
* overhead.
|
||||
*/
|
||||
|
||||
SPI_SNDBLOCK(priv->spi, buffer, buflen);
|
||||
|
||||
/* De-select ENC28J60 chip. */
|
||||
/* De-select ENC28J60 chip
|
||||
*
|
||||
* "The WBM command is terminated by bringing up the CS pin. ..."
|
||||
*/
|
||||
|
||||
enc_deselect(priv);
|
||||
SPI_SELECT(priv->spi, SPIDEV_ETHERNET, false);
|
||||
enc_bmdump(ENC_WBM, buffer, buflen+1);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -880,20 +972,38 @@ static uint16_t enc_rdphy(FAR struct enc_driver_s *priv, uint8_t phyaddr)
|
|||
{
|
||||
uint16_t data = 0;
|
||||
|
||||
/* Set the PHY address (and start the PHY read operation) */
|
||||
/* "To read from a PHY register:
|
||||
*
|
||||
* 1. Write the address of the PHY register to read from into the MIREGADR
|
||||
* register.
|
||||
*/
|
||||
|
||||
enc_wrbreg(priv, ENC_MIREGADR, phyaddr);
|
||||
|
||||
/* 2. Set the MICMD.MIIRD bit. The read operation begins and the
|
||||
* MISTAT.BUSY bit is set.
|
||||
*/
|
||||
|
||||
enc_wrbreg(priv, ENC_MICMD, MICMD_MIIRD);
|
||||
|
||||
/* Wait until the PHY read completes */
|
||||
/* 3. Wait 10.24 µs. Poll the MISTAT.BUSY bit to be certain that the
|
||||
* operation is complete. While busy, the host controller should not
|
||||
* start any MIISCAN operations or write to the MIWRH register.
|
||||
*
|
||||
* When the MAC has obtained the register contents, the BUSY bit will
|
||||
* clear itself.
|
||||
*/
|
||||
|
||||
up_udelay(12);
|
||||
if (enc_waitbreg(priv, ENC_MISTAT, MISTAT_BUSY, 0x00) == OK);
|
||||
{
|
||||
/* Terminate reading */
|
||||
/* 4. Clear the MICMD.MIIRD bit. */
|
||||
|
||||
enc_wrbreg(priv, ENC_MICMD, 0x00);
|
||||
|
||||
/* Get the PHY data */
|
||||
/* 5. Read the desired data from the MIRDL and MIRDH registers. The
|
||||
* order that these bytes are accessed is unimportant."
|
||||
*/
|
||||
|
||||
data = (uint16_t)enc_rdbreg(priv, ENC_MIRDL);
|
||||
data |= (uint16_t)enc_rdbreg(priv, ENC_MIRDH) << 8;
|
||||
|
@ -923,17 +1033,35 @@ static uint16_t enc_rdphy(FAR struct enc_driver_s *priv, uint8_t phyaddr)
|
|||
static void enc_wrphy(FAR struct enc_driver_s *priv, uint8_t phyaddr,
|
||||
uint16_t phydata)
|
||||
{
|
||||
/* Set the PHY register address */
|
||||
/* "To write to a PHY register:
|
||||
*
|
||||
* 1. Write the address of the PHY register to write to into the
|
||||
* MIREGADR register.
|
||||
*/
|
||||
|
||||
enc_wrbreg(priv, ENC_MIREGADR, phyaddr);
|
||||
|
||||
/* Write the PHY data */
|
||||
/* 2. Write the lower 8 bits of data to write into the MIWRL register. */
|
||||
|
||||
enc_wrbreg(priv, ENC_MIWRL, phydata);
|
||||
|
||||
/* 3. Write the upper 8 bits of data to write into the MIWRH register.
|
||||
* Writing to this register automatically begins the MIIM transaction,
|
||||
* so it must be written to after MIWRL. The MISTAT.BUSY bit becomes
|
||||
* set.
|
||||
*/
|
||||
|
||||
enc_wrbreg(priv, ENC_MIWRH, phydata >> 8);
|
||||
|
||||
/* Wait until the PHY write completes */
|
||||
/* The PHY register will be written after the MIIM operation completes,
|
||||
* which takes 10.24 µs. When the write operation has completed, the BUSY
|
||||
* bit will clear itself.
|
||||
*
|
||||
* The host controller should not start any MIISCAN or MIIRD operations
|
||||
* while busy."
|
||||
*/
|
||||
|
||||
up_udelay(12);
|
||||
enc_waitbreg(priv, ENC_MISTAT, MISTAT_BUSY, 0x00);
|
||||
}
|
||||
|
||||
|
@ -984,22 +1112,28 @@ static int enc_transmit(FAR struct enc_driver_s *priv)
|
|||
|
||||
enc_dumppacket("Transmit Packet", priv->dev.d_buf, priv->dev.d_len);
|
||||
|
||||
/* Set transmit buffer start (is this necessary?). */
|
||||
|
||||
enc_wrbreg(priv, ENC_ETXSTL, PKTMEM_TX_START & 0xff);
|
||||
enc_wrbreg(priv, ENC_ETXSTH, PKTMEM_TX_START >> 8);
|
||||
|
||||
/* Reset the write pointer to start of transmit buffer */
|
||||
|
||||
enc_wrbreg(priv, ENC_EWRPTL, PKTMEM_TX_START & 0xff);
|
||||
enc_wrbreg(priv, ENC_EWRPTH, PKTMEM_TX_START >> 8);
|
||||
|
||||
/* Set the TX End pointer based on the size of the packet to send */
|
||||
/* Set the TX End pointer based on the size of the packet to send. Note
|
||||
* that the offset accounts for the control byte at the beginning the
|
||||
* buffer plus the size of the packet data.
|
||||
*/
|
||||
|
||||
txend = PKTMEM_TX_START + priv->dev.d_len;
|
||||
enc_wrbreg(priv, ENC_ETXNDL, txend & 0xff);
|
||||
enc_wrbreg(priv, ENC_ETXNDH, txend >> 8);
|
||||
|
||||
/* Write the per-packet control byte into the transmit buffer */
|
||||
|
||||
enc_wrgreg(priv, ENC_WBM, 0x00);
|
||||
|
||||
/* Copy the packet itself into the transmit buffer */
|
||||
/* Send the WBM command and copy the packet itself into the transmit
|
||||
* buffer at the position of the EWRPT register.
|
||||
*/
|
||||
|
||||
enc_wrbuffer(priv, priv->dev.d_buf, priv->dev.d_len);
|
||||
|
||||
|
@ -1294,14 +1428,15 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
|
|||
priv->stats.pktifs++;
|
||||
#endif
|
||||
|
||||
/* Set the read pointer to the start of the received packet */
|
||||
/* Set the read pointer to the start of the received packet (ERDPT) */
|
||||
|
||||
DEBUGASSERT(priv->nextpkt <= PKTMEM_RX_END);
|
||||
enc_wrbreg(priv, ENC_ERDPTL, (priv->nextpkt));
|
||||
enc_wrbreg(priv, ENC_ERDPTH, (priv->nextpkt) >> 8);
|
||||
|
||||
/* Read the next packet pointer and the 4 byte read status vector (RSV)
|
||||
* at the beginning of the received packet
|
||||
* at the beginning of the received packet. (ERDPT should auto-increment
|
||||
* and wrap to the beginning of the read buffer as necessary)
|
||||
*/
|
||||
|
||||
enc_rdbuffer(priv, rsv, 6);
|
||||
|
@ -1319,7 +1454,9 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
|
|||
priv->nextpkt = (uint16_t)rsv[1] << 8 | (uint16_t)rsv[0];
|
||||
pktlen = (uint16_t)rsv[3] << 8 | (uint16_t)rsv[2];
|
||||
rxstat = (uint16_t)rsv[5] << 8 | (uint16_t)rsv[4];
|
||||
nllvdbg("Receiving packet, pktlen: %d\n", pktlen);
|
||||
|
||||
nllvdbg("Receiving packet, nextpkt: %04x pktlen: %d rxstat: %04x\n",
|
||||
priv->nextpkt, pktlen, rxstat);
|
||||
|
||||
/* Check if the packet was received OK */
|
||||
|
||||
|
@ -1349,7 +1486,10 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
|
|||
|
||||
priv->dev.d_len = pktlen - 4;
|
||||
|
||||
/* Copy the data data from the receive buffer to priv->dev.d_buf */
|
||||
/* Copy the data data from the receive buffer to priv->dev.d_buf.
|
||||
* ERDPT should be correctly positioned from the last call to to
|
||||
* end_rdbuffer (above).
|
||||
*/
|
||||
|
||||
enc_rdbuffer(priv, priv->dev.d_buf, priv->dev.d_len);
|
||||
enc_dumppacket("Received Packet", priv->dev.d_buf, priv->dev.d_len);
|
||||
|
@ -1396,9 +1536,10 @@ static void enc_irqworker(FAR void *arg)
|
|||
|
||||
DEBUGASSERT(priv);
|
||||
|
||||
/* Get exclusive access to uIP. */
|
||||
/* Get exclusive access to both uIP and the SPI bus. */
|
||||
|
||||
lock = uip_lock();
|
||||
enc_lock(priv);
|
||||
|
||||
/* Disable further interrupts by clearing the global interrupt enable bit.
|
||||
* "After an interrupt occurs, the host controller should clear the global
|
||||
|
@ -1582,14 +1723,15 @@ static void enc_irqworker(FAR void *arg)
|
|||
}
|
||||
}
|
||||
|
||||
/* Release lock on uIP */
|
||||
|
||||
uip_unlock(lock);
|
||||
|
||||
/* Enable Ethernet interrupts */
|
||||
|
||||
enc_bfsgreg(priv, ENC_EIE, EIE_INTIE);
|
||||
|
||||
/* Release lock on the SPI bus and uIP */
|
||||
|
||||
enc_unlock(priv);
|
||||
uip_unlock(lock);
|
||||
|
||||
/* Enable GPIO interrupts */
|
||||
|
||||
priv->lower->enable(priv->lower);
|
||||
|
@ -1660,9 +1802,10 @@ static void enc_toworker(FAR void *arg)
|
|||
nlldbg("Tx timeout\n");
|
||||
DEBUGASSERT(priv);
|
||||
|
||||
/* Get exclusive access to uIP. */
|
||||
/* Get exclusive access to both uIP and the SPI bus. */
|
||||
|
||||
lock = uip_lock();
|
||||
enc_lock(priv);
|
||||
|
||||
/* Increment statistics and dump debug info */
|
||||
|
||||
|
@ -1683,8 +1826,9 @@ static void enc_toworker(FAR void *arg)
|
|||
|
||||
(void)uip_poll(&priv->dev, enc_uiptxpoll);
|
||||
|
||||
/* Release lock on uIP */
|
||||
/* Release lock on the SPI bus and uIP */
|
||||
|
||||
enc_unlock(priv);
|
||||
uip_unlock(lock);
|
||||
}
|
||||
|
||||
|
@ -1752,9 +1896,10 @@ static void enc_pollworker(FAR void *arg)
|
|||
|
||||
DEBUGASSERT(priv);
|
||||
|
||||
/* Get exclusive access to uIP. */
|
||||
/* Get exclusive access to both uIP and the SPI bus. */
|
||||
|
||||
lock = uip_lock();
|
||||
enc_lock(priv);
|
||||
|
||||
/* Verify that the hardware is ready to send another packet. The driver
|
||||
* start a transmission process by setting ECON1.TXRTS. When the packet is
|
||||
|
@ -1772,8 +1917,9 @@ static void enc_pollworker(FAR void *arg)
|
|||
(void)uip_timer(&priv->dev, enc_uiptxpoll, ENC_POLLHSEC);
|
||||
}
|
||||
|
||||
/* Release lock on uIP */
|
||||
/* Release lock on the SPI bus and uIP */
|
||||
|
||||
enc_unlock(priv);
|
||||
uip_unlock(lock);
|
||||
|
||||
/* Setup the watchdog poll timer again */
|
||||
|
@ -1846,6 +1992,10 @@ static int enc_ifup(struct uip_driver_s *dev)
|
|||
dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
|
||||
(dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
|
||||
|
||||
/* Lock the SPI bus so that we have exclusive access */
|
||||
|
||||
enc_lock(priv);
|
||||
|
||||
/* Initialize Ethernet interface, set the MAC address, and make sure that
|
||||
* the ENC28J80 is not in power save mode.
|
||||
*/
|
||||
|
@ -1881,6 +2031,9 @@ static int enc_ifup(struct uip_driver_s *dev)
|
|||
priv->lower->enable(priv->lower);
|
||||
}
|
||||
|
||||
/* Un-lock the SPI bus */
|
||||
|
||||
enc_unlock(priv);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -1910,6 +2063,10 @@ static int enc_ifdown(struct uip_driver_s *dev)
|
|||
dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
|
||||
(dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
|
||||
|
||||
/* Lock the SPI bus so that we have exclusive access */
|
||||
|
||||
enc_lock(priv);
|
||||
|
||||
/* Disable the Ethernet interrupt */
|
||||
|
||||
flags = irqsave();
|
||||
|
@ -1927,6 +2084,10 @@ static int enc_ifdown(struct uip_driver_s *dev)
|
|||
|
||||
priv->ifstate = ENCSTATE_DOWN;
|
||||
irqrestore(flags);
|
||||
|
||||
/* Un-lock the SPI bus */
|
||||
|
||||
enc_unlock(priv);
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -1954,10 +2115,13 @@ static int enc_txavail(struct uip_driver_s *dev)
|
|||
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)dev->d_private;
|
||||
irqstate_t flags;
|
||||
|
||||
flags = irqsave();
|
||||
/* Lock the SPI bus so that we have exclusive access */
|
||||
|
||||
enc_lock(priv);
|
||||
|
||||
/* Ignore the notification if the interface is not yet up */
|
||||
|
||||
flags = irqsave();
|
||||
if (priv->ifstate == ENCSTATE_UP)
|
||||
{
|
||||
/* Check if the hardware is ready to send another packet. The driver
|
||||
|
@ -1974,7 +2138,10 @@ static int enc_txavail(struct uip_driver_s *dev)
|
|||
}
|
||||
}
|
||||
|
||||
/* Un-lock the SPI bus */
|
||||
|
||||
irqrestore(flags);
|
||||
enc_unlock(priv);
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
@ -2001,9 +2168,17 @@ static int enc_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
|
|||
{
|
||||
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)dev->d_private;
|
||||
|
||||
/* Lock the SPI bus so that we have exclusive access */
|
||||
|
||||
enc_lock(priv);
|
||||
|
||||
/* Add the MAC address to the hardware multicast routing table */
|
||||
|
||||
#warning "Multicast MAC support not implemented"
|
||||
|
||||
/* Un-lock the SPI bus */
|
||||
|
||||
enc_unlock(priv);
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
@ -2031,9 +2206,17 @@ static int enc_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
|
|||
{
|
||||
FAR struct enc_driver_s *priv = (FAR struct enc_driver_s *)dev->d_private;
|
||||
|
||||
/* Lock the SPI bus so that we have exclusive access */
|
||||
|
||||
enc_lock(priv);
|
||||
|
||||
/* Add the MAC address to the hardware multicast routing table */
|
||||
|
||||
#warning "Multicast MAC support not implemented"
|
||||
|
||||
/* Un-lock the SPI bus */
|
||||
|
||||
enc_unlock(priv);
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
@ -2172,14 +2355,21 @@ static void enc_pwrfull(FAR struct enc_driver_s *priv)
|
|||
|
||||
static void enc_setmacaddr(FAR struct enc_driver_s *priv)
|
||||
{
|
||||
/* Program the hardware with it's MAC address (for filtering) */
|
||||
/* Program the hardware with it's MAC address (for filtering).
|
||||
* MAADR1 MAC Address Byte 1 (MAADR<47:40>), OUI Byte 1
|
||||
* MAADR2 MAC Address Byte 2 (MAADR<39:32>), OUI Byte 2
|
||||
* MAADR3 MAC Address Byte 3 (MAADR<31:24>), OUI Byte 3
|
||||
* MAADR4 MAC Address Byte 4 (MAADR<23:16>)
|
||||
* MAADR5 MAC Address Byte 5 (MAADR<15:8>)
|
||||
* MAADR6 MAC Address Byte 6 (MAADR<7:0>)
|
||||
*/
|
||||
|
||||
enc_wrbreg(priv, ENC_MAADR1, priv->dev.d_mac.ether_addr_octet[5]);
|
||||
enc_wrbreg(priv, ENC_MAADR2, priv->dev.d_mac.ether_addr_octet[4]);
|
||||
enc_wrbreg(priv, ENC_MAADR3, priv->dev.d_mac.ether_addr_octet[3]);
|
||||
enc_wrbreg(priv, ENC_MAADR4, priv->dev.d_mac.ether_addr_octet[2]);
|
||||
enc_wrbreg(priv, ENC_MAADR5, priv->dev.d_mac.ether_addr_octet[1]);
|
||||
enc_wrbreg(priv, ENC_MAADR6, priv->dev.d_mac.ether_addr_octet[0]);
|
||||
enc_wrbreg(priv, ENC_MAADR1, priv->dev.d_mac.ether_addr_octet[0]);
|
||||
enc_wrbreg(priv, ENC_MAADR2, priv->dev.d_mac.ether_addr_octet[1]);
|
||||
enc_wrbreg(priv, ENC_MAADR3, priv->dev.d_mac.ether_addr_octet[2]);
|
||||
enc_wrbreg(priv, ENC_MAADR4, priv->dev.d_mac.ether_addr_octet[3]);
|
||||
enc_wrbreg(priv, ENC_MAADR5, priv->dev.d_mac.ether_addr_octet[4]);
|
||||
enc_wrbreg(priv, ENC_MAADR6, priv->dev.d_mac.ether_addr_octet[5]);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
|
|
@ -304,7 +304,7 @@
|
|||
#define ENC_MAADR3 REGADDR(0x02, 3, 1) /* MAC Address Byte 3 (MAADR<31:24>), OUI Byte 3 */
|
||||
#define ENC_MAADR4 REGADDR(0x03, 3, 1) /* MAC Address Byte 4 (MAADR<23:16>) */
|
||||
#define ENC_MAADR1 REGADDR(0x04, 3, 1) /* MAC Address Byte 1 (MAADR<47:40>), OUI Byte 1 */
|
||||
#define ENC_MAADR2 REGADDR(0x05, 3, 1) /* MAC Address Byte 2 (MAADR<39:32>), OUI Byte */
|
||||
#define ENC_MAADR2 REGADDR(0x05, 3, 1) /* MAC Address Byte 2 (MAADR<39:32>), OUI Byte 2 */
|
||||
#define ENC_EBSTSD REGADDR(0x06, 3, 0) /* Built-in Self-Test Fill Seed (EBSTSD<7:0>) */
|
||||
#define ENC_EBSTCON REGADDR(0x07, 3, 0) /* Built-in Self-Test Control */
|
||||
#define ENC_EBSTCSL REGADDR(0x08, 3, 0) /* Built-in Self-Test Checksum Low Byte (EBSTCS<7:0>) */
|
||||
|
@ -360,12 +360,12 @@
|
|||
|
||||
/* PHY Control Register 1 Register Bit Definitions */
|
||||
|
||||
#define PHCON1_PDPXMD (1 << 8) /* Bit 8: PHY Power-Down */
|
||||
#define PHCON1_PDPXMD (1 << 8) /* Bit 8: PHY Duplex Mode */
|
||||
#define PHCON1_PPWRSV (1 << 11) /* Bit 11: PHY Power-Down */
|
||||
#define PHCON1_PLOOPBK (1 << 14) /* Bit 14: PHY Loopback */
|
||||
#define PHCON1_PRST (1 << 15) /* Bit 15: PHY Software Reset */
|
||||
|
||||
/* HY Status 1 Register Bit Definitions */
|
||||
/* PHY Status 1 Register Bit Definitions */
|
||||
|
||||
#define PHSTAT1_JBSTAT (1 << 1) /* Bit 1: PHY Latching Jabber Status */
|
||||
#define PHSTAT1_LLSTAT (1 << 2) /* Bit 2: PHY Latching Link Status */
|
||||
|
@ -399,7 +399,6 @@
|
|||
#define PHIR_PLNKIF (1 << 4) /* Bit 4: PHY Link Change Interrupt */
|
||||
|
||||
/* PHLCON Regiser Bit Definitions */
|
||||
|
||||
/* Bit 0: Reserved */
|
||||
#define PHLCON_STRCH (1 << 1) /* Bit 1: LED Pulse Stretching Enable */
|
||||
#define PHLCON_LFRQ0 (1 << 2) /* Bit 2: LED Pulse Stretch Time Configuration */
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_clipper.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_closewindow.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_colormap.c
|
||||
*
|
||||
* Copyright (C) 2008-2009,2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_fill.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_redraw.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_setposition.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_setsize.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxbe/nxbe_redraw.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -0,0 +1,152 @@
|
|||
/****************************************************************************
|
||||
* nuttx/graphics/nxconsole/nxcon_bkgd.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* 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
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <semaphore.h>
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/nx/nx.h>
|
||||
#include <nuttx/nx/nxglib.h>
|
||||
|
||||
#include "nxcon_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxcon_redraw
|
||||
*
|
||||
* Description:
|
||||
* Re-draw a portion of the NX console. This function should be called
|
||||
* from the appropriate window callback logic.
|
||||
*
|
||||
* Input Parameters:
|
||||
* handle - A handle previously returned by nx_register, nxtk_register, or
|
||||
* nxtool_register.
|
||||
* rect - The rectangle that needs to be re-drawn (in window relative
|
||||
* coordinates)
|
||||
* more - true: More re-draw requests will follow
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void nxcon_redraw(NXCONSOLE handle, FAR const struct nxgl_rect_s *rect, bool more)
|
||||
{
|
||||
FAR struct nxcon_state_s *priv;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
DEBUGASSERT(handle && rect);
|
||||
gvdbg("rect={(%d,%d),(%d,%d)} more=%s\n",
|
||||
rect->pt1.x, rect->pt1.y, rect->pt2.x, rect->pt2.y,
|
||||
more ? "true" : "false");
|
||||
|
||||
/* Recover our private state structure */
|
||||
|
||||
priv = (FAR struct nxcon_state_s *)handle;
|
||||
|
||||
/* Get exclusive access to the state structure */
|
||||
|
||||
do
|
||||
{
|
||||
ret = nxcon_semwait(priv);
|
||||
|
||||
/* Check for errors */
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
/* The only expected error is if the wait failed because of it
|
||||
* was interrupted by a signal.
|
||||
*/
|
||||
|
||||
DEBUGASSERT(errno == EINTR);
|
||||
}
|
||||
}
|
||||
while (ret < 0);
|
||||
|
||||
/* Fill the rectangular region with the window background color */
|
||||
|
||||
ret = priv->ops->fill(priv, rect, priv->wndo.wcolor);
|
||||
if (ret < 0)
|
||||
{
|
||||
gdbg("fill failed: %d\n", errno);
|
||||
}
|
||||
|
||||
/* Then redraw each character on the display (Only the characters within
|
||||
* the rectangle will actually be redrawn).
|
||||
*/
|
||||
|
||||
for (i = 0; i < priv->nchars; i++)
|
||||
{
|
||||
nxcon_fillchar(priv, rect, &priv->bm[i]);
|
||||
}
|
||||
ret = nxcon_sempost(priv);
|
||||
}
|
|
@ -2,7 +2,7 @@
|
|||
# graphics/nxfonts/Make.defs
|
||||
#
|
||||
# Copyright (C) 2008 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
# graphics/nxfonts/Makefile.sources
|
||||
#
|
||||
# Copyright (C) 2008 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxfonts/nxfonts_bitmaps.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxfonts/nxfonts_convert.c
|
||||
*
|
||||
* Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxfonts/nxfonts_getfont.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -0,0 +1,88 @@
|
|||
/****************************************************************************
|
||||
* graphics/nxfonts/nxfonts_internal.h
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* 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
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __GRAPHICS_NXFONTS_NXFONTS_INTERNAL_H
|
||||
#define __GRAPHICS_NXFONTS_NXFONTS_INTERNAL_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <nuttx/nx/nxfonts.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
#ifndef CONFIG_NXFONTS_CHARBITS
|
||||
# define CONFIG_NXFONTS_CHARBITS 7
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
# define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
# define EXTERN extern
|
||||
#endif
|
||||
|
||||
EXTERN struct nx_fontset_s g_7bitfonts;
|
||||
#if CONFIG_NXFONTS_CHARBITS >= 8
|
||||
EXTERN struct nx_fontset_s g_8bitfonts;
|
||||
#endif
|
||||
EXTERN struct nx_font_s g_fonts;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __GRAPHICS_NXFONTS_NXFONTS_INTERNAL_H */
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/fb/nxsglib_copyrectangle.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/fb/nxglib_fillrectangle.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/lcd/nxsglib_copyrectangle.c
|
||||
*
|
||||
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/lcd/nxglib_fillrectangle.c
|
||||
*
|
||||
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/lcd/nxglib_moverectangle.c
|
||||
*
|
||||
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxglib_bitblit.h
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxglib_circlepts.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxglib_circletraps.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_colorcopy.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_copyrun.h
|
||||
*
|
||||
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_fullrun.h
|
||||
*
|
||||
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_intersecting.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectnonintersecting.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectadd.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectcopy.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectinside.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectintersect.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectoffset.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_nulloverlap.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxglib_rectsize.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_rectunion.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/color/nxglib_rgb2yuv.c
|
||||
*
|
||||
* Copyright (C) 2008, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_runcopy.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_runoffset.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxglib_splitline.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_trapcopy.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_trapoffset.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_vectoradd.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxglib/nxsglib_vectorsubtract.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/color/nxglib_yuv2rgb.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nx_drawcircle.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nx_drawline.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nx_eventnotify.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_fillcircle.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nxmu_openwindow.c
|
||||
*
|
||||
* Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nxmu_releasebkgd.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nxmu_requestbkgd.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nxmu_semtake.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_bitmap.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_close.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -0,0 +1,100 @@
|
|||
/****************************************************************************
|
||||
* graphics/nxsu/nx_closewindow.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* 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
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/nx/nx.h>
|
||||
#include "nxfe.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nx_closewindow
|
||||
*
|
||||
* Description:
|
||||
* Destroy a window created by nx_openwindow.
|
||||
*
|
||||
* Input Parameters:
|
||||
* wnd - The window to be destroyed
|
||||
*
|
||||
* Return:
|
||||
* OK on success; ERROR on failure with errno set appropriately
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nx_closewindow(NXWINDOW hwnd)
|
||||
{
|
||||
#ifdef CONFIG_DEBUG
|
||||
if (!hwnd)
|
||||
{
|
||||
errno = EINVAL;
|
||||
return ERROR;
|
||||
}
|
||||
#endif
|
||||
|
||||
nxbe_closewindow((FAR struct nxbe_window_s *)hwnd);
|
||||
return OK;
|
||||
}
|
||||
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_drawcircle.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_drawline.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_fill.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxmu/nx_fillcircle.c
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_filltrapezoid.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_getposition.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_kbdchin.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_kbdin.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_lower.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_move.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_open.c
|
||||
*
|
||||
* Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -0,0 +1,99 @@
|
|||
/****************************************************************************
|
||||
* graphics/nxsu/nx_raise.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* 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
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/nx/nx.h>
|
||||
#include "nxfe.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nx_raise
|
||||
*
|
||||
* Description:
|
||||
* Bring the specified window to the top of the display.
|
||||
*
|
||||
* Input parameters:
|
||||
* hwnd - the window to be raised
|
||||
*
|
||||
* Returned value:
|
||||
* OK on success; ERROR on failure with errno set appropriately
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nx_raise(NXWINDOW hwnd)
|
||||
{
|
||||
#ifdef CONFIG_DEBUG
|
||||
if (!hwnd)
|
||||
{
|
||||
errno = EINVAL;
|
||||
return ERROR;
|
||||
}
|
||||
#endif
|
||||
|
||||
nxbe_raise((FAR struct nxbe_window_s *)hwnd);
|
||||
return OK;
|
||||
}
|
||||
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_requestbkgd.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_setbgcolor.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nx_setsize.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nxfe.h
|
||||
*
|
||||
* Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nxsu_redrawreq.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxsu/nxsu_reportposition.c
|
||||
*
|
||||
* Copyright (C) 2008-2009,2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxtk/nxtk_bitmapwindow.c
|
||||
*
|
||||
* Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* graphics/nxtk/nxtk_closetoolbar.c
|
||||
*
|
||||
* Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue