#include <dxl_interface.h>
Public Types | |
| enum | InterfaceType { POS, POS_VEL } |
Static Public Member Functions | |
| static InterfaceType | stringToInterfaceType (std::string type) |
Public Attributes | |
| double | command_position = 0 |
| double | command_velocity = 0.15 |
| double | current = 0 |
| int | direction = 0 |
| bool | dont_allow_zero_ticks_vel = true |
| uint8_t | error |
| bool | first_pos_read = true |
| uint8_t | id = 0 |
| bool | in_torque = false |
| InterfaceType | interface_type |
| std::string | joint_name |
| double | position = 0 |
| int32_t | prev_non_zero_velocity_ticks = 4 |
| dxl::spec | spec |
| double | velocity = 0 |
Definition at line 59 of file dxl_interface.h.
| Enumerator | |
|---|---|
| POS | |
| POS_VEL | |
Definition at line 61 of file dxl_interface.h.
|
inlinestatic |
Definition at line 67 of file dxl_interface.h.
| double dxl::motor::command_position = 0 |
Definition at line 83 of file dxl_interface.h.
| double dxl::motor::command_velocity = 0.15 |
Definition at line 84 of file dxl_interface.h.
| double dxl::motor::current = 0 |
Definition at line 82 of file dxl_interface.h.
| int dxl::motor::direction = 0 |
Definition at line 78 of file dxl_interface.h.
| bool dxl::motor::dont_allow_zero_ticks_vel = true |
Definition at line 97 of file dxl_interface.h.
| uint8_t dxl::motor::error |
Definition at line 85 of file dxl_interface.h.
| bool dxl::motor::first_pos_read = true |
Definition at line 104 of file dxl_interface.h.
| uint8_t dxl::motor::id = 0 |
Definition at line 77 of file dxl_interface.h.
| bool dxl::motor::in_torque = false |
Definition at line 79 of file dxl_interface.h.
| InterfaceType dxl::motor::interface_type |
Definition at line 88 of file dxl_interface.h.
| std::string dxl::motor::joint_name |
Definition at line 87 of file dxl_interface.h.
| double dxl::motor::position = 0 |
Definition at line 80 of file dxl_interface.h.
| int32_t dxl::motor::prev_non_zero_velocity_ticks = 4 |
Definition at line 94 of file dxl_interface.h.
| dxl::spec dxl::motor::spec |
Definition at line 75 of file dxl_interface.h.
| double dxl::motor::velocity = 0 |
Definition at line 81 of file dxl_interface.h.