Commit fb0dba44 authored by service-config's avatar service-config

nunchuck over uart

parent 85914615
......@@ -659,7 +659,22 @@ void bldc_interface_set_servo_pos(float pos) {
buffer_append_float16(send_buffer, pos, 1000.0, &send_index);
send_packet_no_fwd(send_buffer, send_index);
}
*/
void bldc_interface_set_uartchuck_data(const chuck_data *chuck_d_remote) {
uint8_t send_buffer[13];
int send_index = 0;
fwd_can_append(send_buffer, &send_index);
send_buffer[send_index++] = COMM_CUSTOM_APP_DATA;
send_buffer[send_index++] = (uint8_t) chuck_d_remote->js_x;
send_buffer[send_index++] = (uint8_t) chuck_d_remote->js_y;
send_buffer[send_index++] = (uint8_t) chuck_d_remote->bt_c;
send_buffer[send_index++] = (uint8_t) chuck_d_remote->bt_z;
buffer_append_int16(send_buffer, chuck_d_remote->acc_x, &send_index);
buffer_append_int16(send_buffer, chuck_d_remote->acc_y, &send_index);
buffer_append_int16(send_buffer, chuck_d_remote->acc_z, &send_index);
send_packet_no_fwd(send_buffer, send_index);
}
/*
void bldc_interface_set_mcconf(const mc_configuration *mcconf) {
int send_index = 0;
fwd_can_append(send_buffer, &send_index);
......
......@@ -52,6 +52,7 @@ void bldc_interface_set_current_brake(float current);
void bldc_interface_set_rpm(int rpm);
void bldc_interface_set_pos(float pos);
void bldc_interface_set_servo_pos(float pos);
void bldc_interface_set_uartchuck_data(const chuck_data *chuck_d_remote); // JL
void bldc_interface_set_mcconf(const mc_configuration *mcconf);
void bldc_interface_set_appconf(const app_configuration *appconf);
......
......@@ -27,7 +27,7 @@
// Settings
#define __CUA_UART_BAUDRATE 9600 //115200
#define __CUA_UART_BAUDRATE 115200 // 9600
// Private functions
static void send_packet(unsigned char *data, int len);
......
......@@ -268,6 +268,16 @@ typedef struct {
float tc_max_diff;
} chuk_config;
typedef struct {
int js_x;
int js_y;
int acc_x;
int acc_y;
int acc_z;
bool bt_c;
bool bt_z;
} chuck_data;
// NRF Datatypes
typedef enum {
NRF_SPEED_250K = 0,
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment