Haptic Controller
Loading...
Searching...
No Matches
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 > Class Template Reference

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.
 
ODriveUserDataget_odrv0_data ()
 Get the odrv0 user data.
 
ODriveUserDataget_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.
 

Detailed Description

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
class CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >

Comms Controller class for managing Canlines.

Template Parameters
ODRIVE_CAN0- The CAN Bus for Odrv0
ODRIVE_CAN1- The CAN Bus for Odrv1

Definition at line 24 of file comm_controller.hpp.

Constructor & Destructor Documentation

◆ CommsController() [1/2]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::CommsController ( )
default

◆ CommsController() [2/2]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::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 )
inline

Construct the comms controller.

Parameters
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_.

Member Function Documentation

◆ comms_timeout()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
bool CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::comms_timeout ( )
inline

◆ find_odrive()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
template<typename T >
void CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::find_odrive ( T odrv_ctrl)
inline

Receive hearbeats on odrives.

Template Parameters
T- Type to bypass template of Odrive_Controller.
Parameters
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().

◆ get_odrv0()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
ODriveCAN & CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv0 ( )
inline

Get odrv0.

Returns
the struct odrv0 object

Definition at line 238 of file comm_controller.hpp.

References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, and OdriveController< CAN >::odrv_.

◆ get_odrv0_data()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
ODriveUserData & CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv0_data ( )
inline

Get the odrv0 user data.

Returns
the struct of user data for odrv0

Definition at line 224 of file comm_controller.hpp.

References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv0_, and OdriveController< CAN >::odrv_user_data_.

◆ get_odrv1()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
ODriveCAN & CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv1 ( )
inline

Get odrv1.

Returns
the struct odrv1 object

Definition at line 245 of file comm_controller.hpp.

References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, and OdriveController< CAN >::odrv_.

◆ get_odrv1_data()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
ODriveUserData & CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::get_odrv1_data ( )
inline

Get the odrv1 user data.

Returns
the struct of user data for odrv1

Definition at line 231 of file comm_controller.hpp.

References CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrv1_, and OdriveController< CAN >::odrv_user_data_.

◆ Initialize()

◆ MakeSignedCANSignal() [1/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
0 ,
32 ,
0. 0001,
0  )
inline

Definition at line 96 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [2/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
0 ,
32 ,
0. 0001,
0  )
inline

Definition at line 90 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [3/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
0 ,
32 ,
0. 0001,
0  )
inline

Definition at line 107 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [4/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
0 ,
32 ,
0. 0001,
0  )
inline

Definition at line 101 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [5/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
32 ,
32 ,
0. 0001,
0  )
inline

Definition at line 97 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [6/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
32 ,
32 ,
0. 0001,
0  )
inline

Definition at line 91 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [7/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
32 ,
32 ,
0. 0001,
0  )
inline

Definition at line 108 of file comm_controller.hpp.

◆ MakeSignedCANSignal() [8/8]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeSignedCANSignal ( float ,
32 ,
32 ,
0. 0001,
0  )
inline

Definition at line 102 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [1/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
10 ,
1 ,
1 ,
0  )
inline

Definition at line 133 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [2/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
10 ,
1 ,
1 ,
0  )
inline

Definition at line 119 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [3/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
4 ,
1 ,
1 ,
0  )
inline

Definition at line 127 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [4/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
4 ,
1 ,
1 ,
0  )
inline

Definition at line 113 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [5/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
5 ,
1 ,
1 ,
0  )
inline

Definition at line 128 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [6/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
5 ,
1 ,
1 ,
0  )
inline

Definition at line 114 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [7/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
6 ,
1 ,
1 ,
0  )
inline

Definition at line 129 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [8/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
6 ,
1 ,
1 ,
0  )
inline

Definition at line 115 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [9/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
7 ,
1 ,
1 ,
0  )
inline

Definition at line 130 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [10/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
7 ,
1 ,
1 ,
0  )
inline

Definition at line 116 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [11/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
8 ,
1 ,
1 ,
0  )
inline

Definition at line 131 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [12/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
8 ,
1 ,
1 ,
0  )
inline

Definition at line 117 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [13/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
9 ,
1 ,
1 ,
0  )
inline

Definition at line 132 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [14/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( bool ,
9 ,
1 ,
1 ,
0  )
inline

Definition at line 118 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [15/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( ControllerState ,
0 ,
4 ,
1 ,
0  )
inline

Definition at line 126 of file comm_controller.hpp.

◆ MakeUnsignedCANSignal() [16/16]

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::MakeUnsignedCANSignal ( ControllerState ,
0 ,
4 ,
1 ,
0  )
inline

Definition at line 112 of file comm_controller.hpp.

◆ startup_odrive()

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
template<typename T >
void CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::startup_odrive ( T odrv_ctrl)
inline

Enable closed loop control on odrive.

Template Parameters
T- Type to bypass template of Odrive_Controller.
Parameters
odrv_ctrlOdrive 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().

◆ Tick()

Member Data Documentation

◆ odrive_can0_

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_256>& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can0_

◆ odrive_can1_

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
FlexCAN_T4<CAN3, RX_SIZE_256, TX_SIZE_256>& CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::odrive_can1_

◆ odrv0_

◆ odrv1_

◆ rx_end_eff_pos_message

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
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().

◆ rx_end_eff_vel_message

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
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().

◆ rx_heartbeat_message

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CANRXMessage<8> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::rx_heartbeat_message
Initial value:
{teensy_can, HEARTBEAT_RX_ID, [this]()
{ handleHeartbeat(); },
odrive0_heartbeat_active_rx, encoder0_active_rx, motor0_active_rx, odrive1_heartbeat_active_rx,
encoder1_active_rx, motor1_active_rx, mirror_system_active_rx, system_state_rx}
ICAN & teensy_can
: Teensy Canline

Values received by the ODrive.

Definition at line 135 of file comm_controller.hpp.

Referenced by CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::Initialize().

◆ teensy_can

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
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().

◆ teensy_heartbeat_timeout

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
bool CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::teensy_heartbeat_timeout = false

◆ timer_group

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
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.

◆ tx_end_eff_pos_message

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CANTXMessage<2> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::tx_end_eff_pos_message
Initial value:
{teensy_can, END_EFFECTOR_POS_TX_ID, 8, 500, timer_group,
end_eff_pos_0_tx, end_eff_pos_1_tx}
VirtualTimerGroup & timer_group
Address of timer group that the comms rely on.

End effectors positions to send to the mirror Teensy.

Definition at line 93 of file comm_controller.hpp.

◆ tx_end_eff_vel_message

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CANTXMessage<2> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::tx_end_eff_vel_message
Initial value:
{teensy_can, END_EFFECTOR_VEL_TX_ID, 8, 500, timer_group, end_eff_vel_0_tx,
end_eff_vel_1_tx}

End effectors velocities to send to the mirror Teensy.

Definition at line 104 of file comm_controller.hpp.

◆ tx_heartbeat_message

template<CAN_DEV_TABLE ODRIVE_CAN0, CAN_DEV_TABLE ODRIVE_CAN1>
CANTXMessage<8> CommsController< ODRIVE_CAN0, ODRIVE_CAN1 >::tx_heartbeat_message
Initial value:
{teensy_can, HEARTBEAT_TX_ID, 1, 10000, timer_group,
odrive0_heartbeat_active_tx,
encoder0_active_tx, motor0_active_tx, odrive1_heartbeat_active_tx,
encoder1_active_tx, motor1_active_tx, mirror_system_active_tx, system_state_tx}

Values to send to the ODrive.

Definition at line 121 of file comm_controller.hpp.


The documentation for this class was generated from the following file: