|
Haptic Controller
|
Comms Controller class for managing Canlines. More...
Public Member Functions | |
| CommsController ()=default | |
| CommsController (VirtualTimerGroup &timer_group, FlexCAN_T4< CAN2, RX_SIZE_256, TX_SIZE_256 > &odrive_can0, FlexCAN_T4< CAN3, RX_SIZE_256, TX_SIZE_256 > &odrive_can1, OdriveController< CAN2 > &odrv0, OdriveController< CAN3 > &odrv1, _MB_ptr F, ICAN &teensy_can) | |
| Construct the comms controller. | |
| MakeSignedCANSignal (float, 0, 32, 0.0001, 0) end_eff_pos_0_tx | |
| MakeSignedCANSignal (float, 32, 32, 0.0001, 0) end_eff_pos_1_tx | |
| MakeSignedCANSignal (float, 0, 32, 0.0001, 0) end_eff_pos_0_rx | |
| MakeSignedCANSignal (float, 32, 32, 0.0001, 0) end_eff_pos_1_rx | |
| MakeSignedCANSignal (float, 0, 32, 0.0001, 0) end_eff_vel_0_tx | |
| MakeSignedCANSignal (float, 32, 32, 0.0001, 0) end_eff_vel_1_tx | |
| MakeSignedCANSignal (float, 0, 32, 0.0001, 0) end_eff_vel_0_rx | |
| MakeSignedCANSignal (float, 32, 32, 0.0001, 0) end_eff_vel_1_rx | |
| MakeUnsignedCANSignal (ControllerState, 0, 4, 1, 0) system_state_tx | |
| MakeUnsignedCANSignal (bool, 4, 1, 1, 0) odrive0_heartbeat_active_tx | |
| MakeUnsignedCANSignal (bool, 5, 1, 1, 0) encoder0_active_tx | |
| MakeUnsignedCANSignal (bool, 6, 1, 1, 0) motor0_active_tx | |
| MakeUnsignedCANSignal (bool, 7, 1, 1, 0) odrive1_heartbeat_active_tx | |
| MakeUnsignedCANSignal (bool, 8, 1, 1, 0) encoder1_active_tx | |
| MakeUnsignedCANSignal (bool, 9, 1, 1, 0) motor1_active_tx | |
| MakeUnsignedCANSignal (bool, 10, 1, 1, 0) mirror_system_active_tx | |
| MakeUnsignedCANSignal (ControllerState, 0, 4, 1, 0) system_state_rx | |
| MakeUnsignedCANSignal (bool, 4, 1, 1, 0) odrive0_heartbeat_active_rx | |
| MakeUnsignedCANSignal (bool, 5, 1, 1, 0) encoder0_active_rx | |
| MakeUnsignedCANSignal (bool, 6, 1, 1, 0) motor0_active_rx | |
| MakeUnsignedCANSignal (bool, 7, 1, 1, 0) odrive1_heartbeat_active_rx | |
| MakeUnsignedCANSignal (bool, 8, 1, 1, 0) encoder1_active_rx | |
| MakeUnsignedCANSignal (bool, 9, 1, 1, 0) motor1_active_rx | |
| MakeUnsignedCANSignal (bool, 10, 1, 1, 0) mirror_system_active_rx | |
| bool | Initialize () |
| Initialize the ODrives and the Teensy CAN, must be called in setup procedure. | |
| void | Tick () |
| Tick Odrive CAN buses and checks timeouts. | |
| template<typename T > | |
| void | find_odrive (T odrv_ctrl) |
| Receive hearbeats on odrives. | |
| template<typename T > | |
| void | startup_odrive (T odrv_ctrl) |
| Enable closed loop control on odrive. | |
| ODriveUserData & | get_odrv0_data () |
| Get the odrv0 user data. | |
| ODriveUserData & | get_odrv1_data () |
| Get the odrv1 user data. | |
| ODriveCAN & | get_odrv0 () |
| Get odrv0. | |
| ODriveCAN & | get_odrv1 () |
| Get odrv1. | |
| bool | comms_timeout () |
| Communication timeout on either Teensy or ODrives. | |
Public Attributes | |
| VirtualTimerGroup & | timer_group |
| Address of timer group that the comms rely on. | |
| FlexCAN_T4< CAN2, RX_SIZE_256, TX_SIZE_256 > & | odrive_can0_ |
| Canline for first odrive. | |
| FlexCAN_T4< CAN3, RX_SIZE_256, TX_SIZE_256 > & | odrive_can1_ |
| Canline for second odrive. | |
| OdriveController< CAN2 > & | odrv0_ |
| Address of first odrive. | |
| OdriveController< CAN3 > & | odrv1_ |
| Address of second odrive. | |
| bool | teensy_heartbeat_timeout = false |
| ICAN & | teensy_can |
| : Teensy Canline | |
| CANTXMessage< 2 > | tx_end_eff_pos_message |
| End effectors positions to send to the mirror Teensy. | |
| CANRXMessage< 2 > | rx_end_eff_pos_message {teensy_can, END_EFFECTOR_POS_RX_ID, end_eff_pos_0_rx, end_eff_pos_1_rx} |
| End effectors positions received by the mirror Teensy. | |
| CANTXMessage< 2 > | tx_end_eff_vel_message |
| End effectors velocities to send to the mirror Teensy. | |
| CANRXMessage< 2 > | rx_end_eff_vel_message {teensy_can, END_EFFECTOR_VEL_RX_ID, end_eff_vel_0_rx, end_eff_vel_1_rx} |
| End effectors velocities received by the mirror Teensy. | |
| CANTXMessage< 8 > | tx_heartbeat_message |
| Values to send to the ODrive. | |
| CANRXMessage< 8 > | rx_heartbeat_message |
| Values received by the ODrive. | |
Comms Controller class for managing Canlines.
| ODRIVE_CAN0 | - The CAN Bus for Odrv0 |
| ODRIVE_CAN1 | - The CAN Bus for Odrv1 |
Definition at line 24 of file comm_controller.hpp.
|
default |
|
inline |
Construct the comms controller.
| timer_group | - The timer to use |
| odrive_can0 | - The Odrv0 Canline |
| odrive_can1 | - The Odrv1 Canline |
| odrv0 | - The Odrive CAN0 Object |
| odrv1 | - The Odrive CAN1 Object |
| F | - The on recieve function for the odrives |
| teensy_can | - The canline for the Teensy |
Definition at line 37 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can0_, and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can1_.
|
inline |
Communication timeout on either Teensy or ODrives.
Definition at line 253 of file comm_controller.hpp.
References ODriveUserData::heartbeat_timeout, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, OdriveController< CAN >::odrv_user_data_, and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::teensy_heartbeat_timeout.
|
inline |
Receive hearbeats on odrives.
| T | - Type to bypass template of Odrive_Controller. |
| odrv_ctrl | - The odrive controller |
Definition at line 186 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().
|
inline |
Get odrv0.
Definition at line 238 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, and OdriveController< CAN >::odrv_.
|
inline |
Get the odrv0 user data.
Definition at line 224 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, and OdriveController< CAN >::odrv_user_data_.
|
inline |
Get odrv1.
Definition at line 245 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, and OdriveController< CAN >::odrv_.
|
inline |
Get the odrv1 user data.
Definition at line 231 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, and OdriveController< CAN >::odrv_user_data_.
|
inline |
Initialize the ODrives and the Teensy CAN, must be called in setup procedure.
Definition at line 143 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::find_odrive(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_end_eff_pos_message, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_end_eff_vel_message, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_heartbeat_message, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::startup_odrive(), OdriveController< CAN >::startup_odrive_checks(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::teensy_can.
|
inline |
Definition at line 96 of file comm_controller.hpp.
|
inline |
Definition at line 90 of file comm_controller.hpp.
|
inline |
Definition at line 107 of file comm_controller.hpp.
|
inline |
Definition at line 101 of file comm_controller.hpp.
|
inline |
Definition at line 97 of file comm_controller.hpp.
|
inline |
Definition at line 91 of file comm_controller.hpp.
|
inline |
Definition at line 108 of file comm_controller.hpp.
|
inline |
Definition at line 102 of file comm_controller.hpp.
|
inline |
Definition at line 133 of file comm_controller.hpp.
|
inline |
Definition at line 119 of file comm_controller.hpp.
|
inline |
Definition at line 127 of file comm_controller.hpp.
|
inline |
Definition at line 113 of file comm_controller.hpp.
|
inline |
Definition at line 128 of file comm_controller.hpp.
|
inline |
Definition at line 114 of file comm_controller.hpp.
|
inline |
Definition at line 129 of file comm_controller.hpp.
|
inline |
Definition at line 115 of file comm_controller.hpp.
|
inline |
Definition at line 130 of file comm_controller.hpp.
|
inline |
Definition at line 116 of file comm_controller.hpp.
|
inline |
Definition at line 131 of file comm_controller.hpp.
|
inline |
Definition at line 117 of file comm_controller.hpp.
|
inline |
Definition at line 132 of file comm_controller.hpp.
|
inline |
Definition at line 118 of file comm_controller.hpp.
|
inline |
Definition at line 126 of file comm_controller.hpp.
|
inline |
Definition at line 112 of file comm_controller.hpp.
|
inline |
Enable closed loop control on odrive.
| T | - Type to bypass template of Odrive_Controller. |
| odrv_ctrl | Odrive controller object |
Definition at line 204 of file comm_controller.hpp.
References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().
|
inline |
Tick Odrive CAN buses and checks timeouts.
Definition at line 166 of file comm_controller.hpp.
References ODriveUserData::heartbeat_timeout, ODriveUserData::last_heartbeat_time, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can0_, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can1_, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, OdriveController< CAN >::odrv_user_data_, and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::teensy_heartbeat_timeout.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::find_odrive(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::startup_odrive().
| FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_256>& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can0_ |
Canline for first odrive.
Definition at line 74 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::CommsController(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
| FlexCAN_T4<CAN3, RX_SIZE_256, TX_SIZE_256>& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can1_ |
Canline for second odrive.
Definition at line 77 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::CommsController(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
| OdriveController<CAN2>& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_ |
Address of first odrive.
Definition at line 80 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::comms_timeout(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv0(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv0_data(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
| OdriveController<CAN3>& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_ |
Address of second odrive.
Definition at line 83 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::comms_timeout(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv1(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv1_data(), CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
| CANRXMessage<2> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_end_eff_pos_message {teensy_can, END_EFFECTOR_POS_RX_ID, end_eff_pos_0_rx, end_eff_pos_1_rx} |
End effectors positions received by the mirror Teensy.
Definition at line 99 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().
| CANRXMessage<2> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_end_eff_vel_message {teensy_can, END_EFFECTOR_VEL_RX_ID, end_eff_vel_0_rx, end_eff_vel_1_rx} |
End effectors velocities received by the mirror Teensy.
Definition at line 110 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().
| CANRXMessage<8> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_heartbeat_message |
Values received by the ODrive.
Definition at line 135 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().
| ICAN& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::teensy_can |
: Teensy Canline
Definition at line 88 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().
| bool CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::teensy_heartbeat_timeout = false |
Definition at line 85 of file comm_controller.hpp.
Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::comms_timeout(), and CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Tick().
| VirtualTimerGroup& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::timer_group |
Address of timer group that the comms rely on.
Definition at line 71 of file comm_controller.hpp.
| CANTXMessage<2> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::tx_end_eff_pos_message |
End effectors positions to send to the mirror Teensy.
Definition at line 93 of file comm_controller.hpp.
| CANTXMessage<2> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::tx_end_eff_vel_message |
End effectors velocities to send to the mirror Teensy.
Definition at line 104 of file comm_controller.hpp.
| CANTXMessage<8> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::tx_heartbeat_message |
Values to send to the ODrive.
Definition at line 121 of file comm_controller.hpp.