123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415 |
- #include "SIM_Gimbal.h"
- #include <stdio.h>
- #include "SIM_Aircraft.h"
- #include <AP_InertialSensor/AP_InertialSensor.h>
- extern const AP_HAL::HAL& hal;
- namespace SITL {
- Gimbal::Gimbal(const struct sitl_fdm &_fdm) :
- fdm(_fdm),
- target_address("127.0.0.1"),
- target_port(5762),
- lower_joint_limits(radians(-40), radians(-135), radians(-7.5)),
- upper_joint_limits(radians(40), radians(45), radians(7.5)),
- travelLimitGain(20),
- reporting_period_ms(10),
- seen_heartbeat(false),
- seen_gimbal_control(false),
- mav_socket(false)
- {
- memset(&mavlink, 0, sizeof(mavlink));
- fdm.quaternion.rotation_matrix(dcm);
- }
- void Gimbal::update(void)
- {
-
- uint32_t now_us = AP_HAL::micros();
- float delta_t = (now_us - last_update_us) * 1.0e-6f;
- last_update_us = now_us;
- Matrix3f vehicle_dcm;
- fdm.quaternion.rotation_matrix(vehicle_dcm);
- const Vector3f &vehicle_gyro = AP::ins().get_gyro();
- const Vector3f &vehicle_accel_body = AP::ins().get_accel();
-
- Vector3f demRateRaw = demanded_angular_rate;
-
-
- Vector3f copterAngRate_G = dcm.transposed()*vehicle_dcm*vehicle_gyro;
-
-
-
- Vector3f relativeGimbalRate = demanded_angular_rate - copterAngRate_G;
-
-
- Matrix3f rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm;
- joint_angles = rotmat_copter_gimbal.transposed().to_euler312();
-
- Vector3f upperRatelimit = -(joint_angles - upper_joint_limits) * travelLimitGain;
- Vector3f lowerRatelimit = -(joint_angles - lower_joint_limits) * travelLimitGain;
-
- float rollAngle = joint_angles.x;
- float elevAngle = joint_angles.y;
- Matrix3f matrix = Matrix3f(Vector3f(cosf(elevAngle), 0, sinf(elevAngle)),
- Vector3f(sinf(elevAngle)*tanf(rollAngle), 1, -cosf(elevAngle)*tanf(rollAngle)),
- Vector3f(-sinf(elevAngle)/cosf(rollAngle), 0, cosf(elevAngle)/cosf(rollAngle)));
- Vector3f gimbalJointRates = matrix * relativeGimbalRate;
-
- gimbalJointRates.x = constrain_float(gimbalJointRates.x, lowerRatelimit.x, upperRatelimit.x);
- gimbalJointRates.y = constrain_float(gimbalJointRates.y, lowerRatelimit.y, upperRatelimit.y);
- gimbalJointRates.z = constrain_float(gimbalJointRates.z, lowerRatelimit.z, upperRatelimit.z);
-
- matrix = Matrix3f(Vector3f(cosf(elevAngle), 0, -cosf(rollAngle)*sinf(elevAngle)),
- Vector3f(0, 1, sinf(rollAngle)),
- Vector3f(sinf(elevAngle), 0, cosf(elevAngle)*cosf(rollAngle)));
- relativeGimbalRate = matrix * gimbalJointRates;
-
-
-
-
-
- gimbal_angular_rate = demRateRaw;
-
- dcm.rotate(gimbal_angular_rate*delta_t);
- dcm.normalize();
-
- rotmat_copter_gimbal = dcm.transposed() * vehicle_dcm;
-
- joint_angles = rotmat_copter_gimbal.transposed().to_euler312();
-
- gyro = gimbal_angular_rate + true_gyro_bias;
-
- delta_angle += gyro * delta_t;
-
- Vector3f copter_accel_earth = vehicle_dcm * vehicle_accel_body;
- Vector3f accel = dcm.transposed() * copter_accel_earth;
-
- delta_velocity += accel * delta_t;
-
- send_report();
- }
- static struct gimbal_param {
- const char *name;
- float value;
- } gimbal_params[] = {
- {"GMB_OFF_ACC_X", 0},
- {"GMB_OFF_ACC_Y", 0},
- {"GMB_OFF_ACC_Z", 0},
- {"GMB_GN_ACC_X", 0},
- {"GMB_GN_ACC_Y", 0},
- {"GMB_GN_ACC_Z", 0},
- {"GMB_OFF_GYRO_X", 0},
- {"GMB_OFF_GYRO_Y", 0},
- {"GMB_OFF_GYRO_Z", 0},
- {"GMB_OFF_JNT_X", 0},
- {"GMB_OFF_JNT_Y", 0},
- {"GMB_OFF_JNT_Z", 0},
- {"GMB_K_RATE", 0},
- {"GMB_POS_HOLD", 0},
- {"GMB_MAX_TORQUE", 0},
- {"GMB_SND_TORQUE", 0},
- {"GMB_SYSID", 0},
- {"GMB_FLASH", 0},
- };
- struct gimbal_param *Gimbal::param_find(const char *name)
- {
- for (uint8_t i=0; i<ARRAY_SIZE(gimbal_params); i++) {
- if (strncmp(name, gimbal_params[i].name, 16) == 0) {
- return &gimbal_params[i];
- }
- }
- return nullptr;
- }
-
- void Gimbal::param_send(const struct gimbal_param *p)
- {
- mavlink_message_t msg;
- mavlink_param_value_t param_value;
- strncpy(param_value.param_id, p->name, sizeof(param_value.param_id));
- param_value.param_value = p->value;
- param_value.param_count = 0;
- param_value.param_index = 0;
- param_value.param_type = MAV_PARAM_TYPE_REAL32;
- mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
- uint8_t saved_seq = chan0_status->current_tx_seq;
- chan0_status->current_tx_seq = mavlink.seq;
- uint16_t len = mavlink_msg_param_value_encode(vehicle_system_id,
- vehicle_component_id,
- &msg, ¶m_value);
- chan0_status->current_tx_seq = saved_seq;
- uint8_t msgbuf[len];
- len = mavlink_msg_to_send_buffer(msgbuf, &msg);
- if (len > 0) {
- mav_socket.send(msgbuf, len);
- }
- }
-
- void Gimbal::send_report(void)
- {
- uint32_t now = AP_HAL::millis();
- if (now < 10000) {
-
-
-
- return;
- }
- if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {
- ::printf("Gimbal connected to %s:%u\n", target_address, (unsigned)target_port);
- mavlink.connected = true;
- }
- if (!mavlink.connected) {
- return;
- }
- if (param_send_last_ms && now - param_send_last_ms > 100) {
- param_send(&gimbal_params[param_send_idx]);
- if (++param_send_idx == ARRAY_SIZE(gimbal_params)) {
- printf("Finished sending parameters\n");
- param_send_last_ms = 0;
- }
- }
-
- uint8_t buf[100];
- ssize_t ret;
- while ((ret=mav_socket.recv(buf, sizeof(buf), 0)) > 0) {
- for (uint8_t i=0; i<ret; i++) {
- mavlink_message_t msg;
- mavlink_status_t status;
- if (mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status,
- buf[i],
- &msg, &status) == MAVLINK_FRAMING_OK) {
- switch (msg.msgid) {
- case MAVLINK_MSG_ID_HEARTBEAT: {
- mavlink_heartbeat_t pkt;
- mavlink_msg_heartbeat_decode(&msg, &pkt);
- printf("Gimbal: got HB type=%u autopilot=%u base_mode=0x%x\n", pkt.type, pkt.autopilot, pkt.base_mode);
- if (!seen_heartbeat) {
- seen_heartbeat = true;
- vehicle_component_id = msg.compid;
- vehicle_system_id = msg.sysid;
- ::printf("Gimbal using srcSystem %u\n", (unsigned)vehicle_system_id);
- }
- break;
- }
- case MAVLINK_MSG_ID_GIMBAL_CONTROL: {
- static uint32_t counter;
- if (counter++ % 100 == 0) {
- printf("GIMBAL_CONTROL %u\n", counter);
- }
- mavlink_gimbal_control_t pkt;
- mavlink_msg_gimbal_control_decode(&msg, &pkt);
- demanded_angular_rate = Vector3f(pkt.demanded_rate_x,
- pkt.demanded_rate_y,
- pkt.demanded_rate_z);
-
- supplied_gyro_bias.zero();
- seen_gimbal_control = true;
- break;
- }
- case MAVLINK_MSG_ID_PARAM_SET: {
- mavlink_param_set_t pkt;
- mavlink_msg_param_set_decode(&msg, &pkt);
- printf("Gimbal got PARAM_SET %.16s %f\n", pkt.param_id, pkt.param_value);
- struct gimbal_param *p = param_find(pkt.param_id);
- if (p) {
- p->value = pkt.param_value;
- param_send(p);
- }
- break;
- }
- case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
- mavlink_param_request_list_t pkt;
- mavlink_msg_param_request_list_decode(&msg, &pkt);
- if (pkt.target_system == 0 && pkt.target_component == MAV_COMP_ID_GIMBAL) {
-
- param_send_idx = 0;
- param_send_last_ms = AP_HAL::millis();
- }
- printf("Gimbal sending %u parameters\n", (unsigned)ARRAY_SIZE(gimbal_params));
- break;
- }
- default:
- printf("Gimbal got unexpected msg %u\n", msg.msgid);
- break;
- }
- }
- }
- }
- if (!seen_heartbeat) {
- return;
- }
- mavlink_message_t msg;
- uint16_t len;
- if (now - last_heartbeat_ms >= 1000) {
- mavlink_heartbeat_t heartbeat;
- heartbeat.type = MAV_TYPE_GIMBAL;
- heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
- heartbeat.base_mode = 0;
- heartbeat.system_status = 0;
- heartbeat.mavlink_version = 0;
- heartbeat.custom_mode = 0;
-
- mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
- uint8_t saved_seq = chan0_status->current_tx_seq;
- chan0_status->current_tx_seq = mavlink.seq;
- len = mavlink_msg_heartbeat_encode(vehicle_system_id,
- vehicle_component_id,
- &msg, &heartbeat);
- chan0_status->current_tx_seq = saved_seq;
- mav_socket.send(&msg.magic, len);
- last_heartbeat_ms = now;
- }
-
- uint32_t now_us = AP_HAL::micros();
- if (now_us - last_report_us > reporting_period_ms*1000UL) {
- mavlink_gimbal_report_t gimbal_report;
- float delta_time = (now_us - last_report_us) * 1.0e-6f;
- last_report_us = now_us;
- gimbal_report.target_system = vehicle_system_id;
- gimbal_report.target_component = vehicle_component_id;
- gimbal_report.delta_time = delta_time;
- gimbal_report.delta_angle_x = delta_angle.x;
- gimbal_report.delta_angle_y = delta_angle.y;
- gimbal_report.delta_angle_z = delta_angle.z;
- gimbal_report.delta_velocity_x = delta_velocity.x;
- gimbal_report.delta_velocity_y = delta_velocity.y;
- gimbal_report.delta_velocity_z = delta_velocity.z;
- gimbal_report.joint_roll = joint_angles.x;
- gimbal_report.joint_el = joint_angles.y;
- gimbal_report.joint_az = joint_angles.z;
- mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
- uint8_t saved_seq = chan0_status->current_tx_seq;
- chan0_status->current_tx_seq = mavlink.seq;
- len = mavlink_msg_gimbal_report_encode(vehicle_system_id,
- vehicle_component_id,
- &msg, &gimbal_report);
- chan0_status->current_tx_seq = saved_seq;
- uint8_t msgbuf[len];
- len = mavlink_msg_to_send_buffer(msgbuf, &msg);
- if (len > 0) {
- mav_socket.send(msgbuf, len);
- }
- delta_velocity.zero();
- delta_angle.zero();
- }
- }
- }
|