MRPT
2.0.4
|
A USB-interface for a custom "robotic neck" designed at MAPIR lab.
Definition at line 19 of file CServoeNeck.h.
#include <mrpt/hwdrivers/CServoeNeck.h>
Public Types | |
enum | TSeekOrigin { sFromBeginning = 0, sFromCurrent = 1, sFromEnd = 2 } |
Used in CStream::Seek. More... | |
Public Member Functions | |
CServoeNeck () | |
~CServoeNeck () override | |
bool | queryFirmwareVersion (std::string &out_firmwareVersion) |
Gets the firmware version of the eNeck board. More... | |
bool | getCurrentAngle (double &angle, const uint8_t servo=0) |
Gets the current angle of the servo (in radians within (-pi,pi)) More... | |
bool | setAngle (double angle, const uint8_t servo=0, bool fast=false) |
Turns the servo up to the specified angle (in radians in the range -pi,pi, other values will be saturated to the maximum or the mininum) More... | |
bool | setAngleAndSpeed (double angle, const uint8_t servo, const uint8_t speed) |
Turns the servo up to the specified angle (in radians in the range -pi,pi, other values will be saturated to the maximum or the mininum) More... | |
bool | setAngleWithFilter (double angle, const uint8_t servo=0, bool fast=false) |
Turns the servo up to the specified angle (in radians in the range -pi,pi) filtered by average with the last N specified angles. More... | |
bool | disableServo (const uint8_t servo=0) |
Disables the servo so the neck will be loose. More... | |
bool | enableServo (const uint8_t servo=0) |
Enables the servo so the neck will be tight. More... | |
bool | center (const uint8_t servo=0) |
Centers the servo at zero position. More... | |
double | getTruncateFactor () |
Gets the truncate factor of the turn. More... | |
void | setTruncateFactor (const double factor) |
Gets the truncate factor of the turn. More... | |
void | setNumberOfPreviousAngles (const unsigned int number) |
Gets the truncate factor of the turn. More... | |
unsigned int | getNumberOfPreviousAngles () |
Gets the truncate factor of the turn. More... | |
void | setOffsets (float offset0, float offset1, float offset2) |
Load the Offset values for each servo. More... | |
bool | isOpen () |
Checks whether the chip has been successfully open. More... | |
void | OpenBySerialNumber (const std::string &serialNumber) |
Open by device serial number. More... | |
void | OpenByDescription (const std::string &description) |
Open by device description. More... | |
void | Close () |
Close the USB device. More... | |
void | ResetDevice () |
Reset the USB device. More... | |
void | Purge () |
Purge the I/O buffers. More... | |
void | SetLatencyTimer (unsigned char latency_ms) |
Change the latency timer (in milliseconds) implemented on the FTDI chip: for a few ms, data is not sent to the PC waiting for possible more data, to save USB trafic. More... | |
void | SetTimeouts (unsigned long dwReadTimeout_ms, unsigned long dwWriteTimeout_ms) |
Change read & write timeouts, in milliseconds. More... | |
void | ListAllDevices (TFTDIDeviceList &outList) |
Generates a list with all FTDI devices connected right now. More... | |
size_t | ReadSync (void *Buffer, size_t Count) |
Tries to read, raising no exception if not all the bytes are available, but raising one if there is some communication error. More... | |
size_t | WriteSync (const void *Buffer, size_t Count) |
Tries to write, raising no exception if not all the bytes are available, but raising one if there is some communication error. More... | |
size_t | ReadBufferImmediate (void *Buffer, size_t Count) override |
Reads a block of bytes from the stream into Buffer, and returns the amound of bytes actually read, without waiting for more extra bytes to arrive (just those already enqued in the stream). More... | |
size_t | Read (void *Buffer, size_t Count) override |
Introduces a pure virtual method responsible for reading from the stream. More... | |
size_t | Write (const void *Buffer, size_t Count) override |
Introduces a pure virtual method responsible for writing to the stream. More... | |
uint64_t | Seek (int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) override |
This virtual method does nothing in this class. More... | |
virtual uint64_t | Seek (int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning)=0 |
Introduces a pure virtual method for moving to a specified position in the streamed resource. More... | |
uint64_t | getTotalBytesCount () const override |
This virtual method does nothing in this class. More... | |
uint64_t | getPosition () const override |
This virtual method does nothing in this class. More... | |
virtual int | printf (const char *fmt,...) MRPT_printf_format_check(2 |
Writes a string to the stream in a textual form. More... | |
template<typename CONTAINER_TYPE > | |
virtual int void | printf_vector (const char *fmt, const CONTAINER_TYPE &V, char separator=',') |
Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element T . More... | |
bool | getline (std::string &out_str) |
Reads from the stream until a ' ' character is found ('' characters are ignored). More... | |
Protected Member Functions | |
bool | setRegisterValue (const uint16_t value, const uint8_t servo=0, bool fast=false) |
bool | setRegisterValueAndSpeed (const uint16_t value, const uint8_t servo, const uint16_t speed) |
bool | getRegisterValue (uint16_t &value, const uint8_t servo=0) |
void | ftdi_read (void *lpvBuffer, unsigned long dwBuffSize, unsigned long *lpdwBytesRead) |
void | ftdi_write (const void *lpvBuffer, unsigned long dwBuffSize, unsigned long *lpdwBytes) |
Protected Attributes | |
std::string | m_usbSerialNumber |
A copy of the device serial number (to open the USB FTDI chip). More... | |
double | m_MaxValue {10000} |
The value set in the ICR register within the ATMEGA16 controller. More... | |
double | m_TruncateFactor {0.5} |
The range of turn of the servo will be truncated to "+-m_truncate_factor*(pi/2)". More... | |
std::deque< double > | m_PrevAngles |
A vector containing the last N angles which where passed to the servo (for averaging) More... | |
unsigned int | m_NumPrevAngles {5} |
Number of previous angles to store for averaging. More... | |
std::vector< float > | m_offsets |
The offset used for each servo. More... | |
mrpt::containers::circular_buffer< uint8_t > | m_readBuffer |
Used in Read. More... | |
Private Member Functions | |
unsigned int | angle2RegValue (const double angle) |
Converts from a decimal angle (in radians) to the corresponding register value for the ATMEGA16 controller (for inner use only). More... | |
double | regValue2angle (const uint16_t value) |
Converts from a certain value of the ATMEGA16 PWM register to the corresponding decimal angle (for inner use only). More... | |
bool | checkConnectionAndConnect () |
Tries to connect to the USB device (if disconnected). More... | |
|
inherited |
Used in CStream::Seek.
Enumerator | |
---|---|
sFromBeginning | |
sFromCurrent | |
sFromEnd |
Definition at line 32 of file io/CStream.h.
CServoeNeck::CServoeNeck | ( | ) |
Definition at line 30 of file CServoeNeck.cpp.
References m_offsets.
|
overridedefault |
|
private |
Converts from a decimal angle (in radians) to the corresponding register value for the ATMEGA16 controller (for inner use only).
The | angle to convert. |
Definition at line 76 of file CServoeNeck.cpp.
References M_PI.
Referenced by center(), setAngle(), and setAngleAndSpeed().
bool CServoeNeck::center | ( | const uint8_t | servo = 0 | ) |
Centers the servo at zero position.
Definition at line 392 of file CServoeNeck.cpp.
References angle2RegValue(), m_offsets, and setRegisterValue().
|
private |
Tries to connect to the USB device (if disconnected).
Definition at line 401 of file CServoeNeck.cpp.
References mrpt::comms::CInterfaceFTDI::Close(), mrpt::comms::CInterfaceFTDI::isOpen(), m_usbSerialNumber, mrpt::comms::CInterfaceFTDI::OpenBySerialNumber(), mrpt::comms::CInterfaceFTDI::Purge(), mrpt::comms::CInterfaceFTDI::SetLatencyTimer(), and mrpt::comms::CInterfaceFTDI::SetTimeouts().
Referenced by queryFirmwareVersion().
|
inherited |
Close the USB device.
Definition at line 287 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::containers::circular_buffer< T >::clear(), mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pClose, mrpt::comms::CInterfaceFTDI::m_readBuffer, MRPT_END, and MRPT_START.
Referenced by checkConnectionAndConnect(), mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), disableServo(), enableServo(), mrpt::comms::CInterfaceFTDI::ftdi_open(), mrpt::comms::CInterfaceFTDI::ftdi_openEx(), getRegisterValue(), queryFirmwareVersion(), setRegisterValue(), setRegisterValueAndSpeed(), and mrpt::comms::CInterfaceFTDI::~CInterfaceFTDI().
bool CServoeNeck::disableServo | ( | const uint8_t | servo = 0 | ) |
Disables the servo so the neck will be loose.
Servo | the id of the servo to move (in our ATMEGA16, from 0 to 2). |
Definition at line 330 of file CServoeNeck.cpp.
References mrpt::serialization::archiveFrom(), mrpt::comms::CInterfaceFTDI::Close(), mrpt::serialization::CMessage::content, mrpt::comms::CInterfaceFTDI::isOpen(), and mrpt::serialization::CMessage::type.
bool CServoeNeck::enableServo | ( | const uint8_t | servo = 0 | ) |
Enables the servo so the neck will be tight.
Servo | the id of the servo to move (in our ATMEGA16, from 0 to 2). |
Definition at line 361 of file CServoeNeck.cpp.
References mrpt::serialization::archiveFrom(), mrpt::comms::CInterfaceFTDI::Close(), mrpt::serialization::CMessage::content, mrpt::comms::CInterfaceFTDI::isOpen(), and mrpt::serialization::CMessage::type.
|
protectedinherited |
Definition at line 303 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pRead, MRPT_END, and MRPT_START.
Referenced by mrpt::comms::CInterfaceFTDI::Read(), and mrpt::comms::CInterfaceFTDI::ReadBufferImmediate().
|
protectedinherited |
Definition at line 315 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pWrite, MRPT_END, and MRPT_START.
Referenced by mrpt::comms::CInterfaceFTDI::Write().
bool CServoeNeck::getCurrentAngle | ( | double & | angle, |
const uint8_t | servo = 0 |
||
) |
Gets the current angle of the servo (in radians within (-pi,pi))
Angle | [OUT] The current angle. |
Servo | [IN] The id of the servo (in our ATMEGA16, from 0 to 2). |
Definition at line 239 of file CServoeNeck.cpp.
References getRegisterValue(), and regValue2angle().
|
inherited |
Reads from the stream until a '
' character is found ('' characters are ignored).
Definition at line 69 of file CStream.cpp.
|
inline |
Gets the truncate factor of the turn.
Definition at line 111 of file CServoeNeck.h.
References m_NumPrevAngles.
|
overridevirtualinherited |
This virtual method does nothing in this class.
Implements mrpt::io::CStream.
Definition at line 67 of file CInterfaceFTDI_common.cpp.
|
protected |
Definition at line 200 of file CServoeNeck.cpp.
References mrpt::serialization::archiveFrom(), mrpt::comms::CInterfaceFTDI::Close(), mrpt::serialization::CMessage::content, mrpt::comms::CInterfaceFTDI::isOpen(), and mrpt::serialization::CMessage::type.
Referenced by getCurrentAngle().
|
overridevirtualinherited |
This virtual method does nothing in this class.
Implements mrpt::io::CStream.
Definition at line 66 of file CInterfaceFTDI_common.cpp.
|
inline |
Gets the truncate factor of the turn.
Definition at line 93 of file CServoeNeck.h.
References m_TruncateFactor.
|
inherited |
Checks whether the chip has been successfully open.
Definition at line 181 of file CInterfaceFTDI_WIN.cpp.
References mrpt::comms::CInterfaceFTDI::m_ftHandle.
Referenced by checkConnectionAndConnect(), disableServo(), enableServo(), mrpt::comms::CInterfaceFTDI::ftdi_open(), mrpt::comms::CInterfaceFTDI::ftdi_openEx(), getRegisterValue(), setRegisterValue(), and setRegisterValueAndSpeed().
|
inherited |
Generates a list with all FTDI devices connected right now.
Definition at line 244 of file CInterfaceFTDI_WIN.cpp.
References mrpt::comms::TFTDIDevice::ftdi_description, mrpt::comms::CInterfaceFTDI::ftdi_listDevices(), mrpt::comms::TFTDIDevice::ftdi_serial, MRPT_END, and MRPT_START.
|
inherited |
Open by device description.
Definition at line 439 of file CInterfaceFTDI_WIN.cpp.
References mrpt::containers::circular_buffer< T >::clear(), FT_OPEN_BY_DESCRIPTION, mrpt::comms::CInterfaceFTDI::ftdi_openEx(), mrpt::comms::CInterfaceFTDI::m_readBuffer, MRPT_END, and MRPT_START.
|
inherited |
Open by device serial number.
Definition at line 427 of file CInterfaceFTDI_WIN.cpp.
References mrpt::containers::circular_buffer< T >::clear(), FT_OPEN_BY_SERIAL_NUMBER, mrpt::comms::CInterfaceFTDI::ftdi_openEx(), mrpt::comms::CInterfaceFTDI::m_readBuffer, MRPT_END, and MRPT_START.
Referenced by checkConnectionAndConnect().
|
virtualinherited |
Writes a string to the stream in a textual form.
Definition at line 30 of file CStream.cpp.
References MRPT_END, MRPT_START, and mrpt::system::os::vsnprintf().
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::io::CStream::printf_vector(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), and mrpt::apps::ICP_SLAM_App_Base::run().
|
inlineinherited |
Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element T
.
CONTAINER_TYPE | can be any vector<T>, deque<T> or alike. |
Definition at line 102 of file io/CStream.h.
References mrpt::io::CStream::printf().
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel().
|
inherited |
Purge the I/O buffers.
Definition at line 339 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), mrpt::containers::circular_buffer< T >::clear(), FT_PURGE_RX, FT_PURGE_TX, mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pPurge, mrpt::comms::CInterfaceFTDI::m_readBuffer, MRPT_END, and MRPT_START.
Referenced by checkConnectionAndConnect().
bool CServoeNeck::queryFirmwareVersion | ( | std::string & | out_firmwareVersion | ) |
Gets the firmware version of the eNeck board.
out_firmwareVersion | [OUTPUT] A string containing the firmware version. |
Definition at line 45 of file CServoeNeck.cpp.
References mrpt::serialization::archiveFrom(), checkConnectionAndConnect(), mrpt::comms::CInterfaceFTDI::Close(), mrpt::serialization::CMessage::getContentAsString(), and mrpt::serialization::CMessage::type.
|
overridevirtualinherited |
Introduces a pure virtual method responsible for reading from the stream.
It integrates a cache buffer to speed-up sequences of many, small readings.
Implements mrpt::io::CStream.
Definition at line 18 of file CInterfaceFTDI_common.cpp.
References mrpt::containers::circular_buffer< T >::available(), mrpt::comms::CInterfaceFTDI::ftdi_read(), mrpt::comms::CInterfaceFTDI::m_readBuffer, mrpt::containers::circular_buffer< T >::pop_many(), mrpt::containers::circular_buffer< T >::push_many(), and mrpt::containers::circular_buffer< T >::size().
Referenced by mrpt::comms::CInterfaceFTDI::ReadSync().
|
overridevirtualinherited |
Reads a block of bytes from the stream into Buffer, and returns the amound of bytes actually read, without waiting for more extra bytes to arrive (just those already enqued in the stream).
In this class this method actually behaves as expected and does not fallback to ReadBuffer().
std::exception | On any error, or if ZERO bytes are read. |
Reimplemented from mrpt::io::CStream.
Definition at line 68 of file CInterfaceFTDI_common.cpp.
References mrpt::comms::CInterfaceFTDI::ftdi_read().
|
inlineinherited |
Tries to read, raising no exception if not all the bytes are available, but raising one if there is some communication error.
Definition at line 129 of file CInterfaceFTDI.h.
References mrpt::comms::CInterfaceFTDI::Read().
|
private |
Converts from a certain value of the ATMEGA16 PWM register to the corresponding decimal angle (for inner use only).
The | value to convert. |
Definition at line 98 of file CServoeNeck.cpp.
References M_PI.
Referenced by getCurrentAngle().
|
inherited |
Reset the USB device.
Definition at line 327 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), mrpt::containers::circular_buffer< T >::clear(), mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pResetDevice, mrpt::comms::CInterfaceFTDI::m_readBuffer, MRPT_END, and MRPT_START.
|
pure virtualinherited |
Introduces a pure virtual method for moving to a specified position in the streamed resource.
he Origin parameter indicates how to interpret the Offset parameter. Origin should be one of the following values:
Implemented in mrpt::io::CPipeBaseEndPoint, mrpt::io::CFileStream, mrpt::io::CFileGZInputStream, mrpt::io::CFileGZOutputStream, mrpt::io::CMemoryStream, mrpt::io::CFileOutputStream, and mrpt::io::CFileInputStream.
|
overrideinherited |
This virtual method does nothing in this class.
Definition at line 61 of file CInterfaceFTDI_common.cpp.
bool CServoeNeck::setAngle | ( | double | angle, |
const uint8_t | servo = 0 , |
||
bool | fast = false |
||
) |
Turns the servo up to the specified angle (in radians in the range -pi,pi, other values will be saturated to the maximum or the mininum)
Angle | the desired angle to turn. |
Servo | the id of the servo to move (in our ATMEGA16, from 0 to 2). |
Fast | indicates if the servo must reach the angle at maximum speed |
Definition at line 254 of file CServoeNeck.cpp.
References angle2RegValue(), m_offsets, M_PI, m_TruncateFactor, mrpt::RAD2DEG(), and setRegisterValue().
Referenced by setAngleWithFilter().
bool CServoeNeck::setAngleAndSpeed | ( | double | angle, |
const uint8_t | servo, | ||
const uint8_t | speed | ||
) |
Turns the servo up to the specified angle (in radians in the range -pi,pi, other values will be saturated to the maximum or the mininum)
Angle | the desired angle to turn. |
Servo | the id of the servo to move (in our ATMEGA16, from 0 to 2). |
Speed | indicates the speed of the servo |
Definition at line 284 of file CServoeNeck.cpp.
References angle2RegValue(), m_offsets, M_PI, m_TruncateFactor, and setRegisterValueAndSpeed().
bool CServoeNeck::setAngleWithFilter | ( | double | angle, |
const uint8_t | servo = 0 , |
||
bool | fast = false |
||
) |
Turns the servo up to the specified angle (in radians in the range -pi,pi) filtered by average with the last N specified angles.
Angle | the new desired angle to turn. |
Servo | the id of the servo to move (in our ATMEGA16, from 0 to 2). |
Fast | indicates if the servo must reach the angle at maximum speed |
Definition at line 307 of file CServoeNeck.cpp.
References m_NumPrevAngles, m_PrevAngles, and setAngle().
|
inherited |
Change the latency timer (in milliseconds) implemented on the FTDI chip: for a few ms, data is not sent to the PC waiting for possible more data, to save USB trafic.
Definition at line 373 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pSetLatencyTimer, MRPT_END, and MRPT_START.
Referenced by checkConnectionAndConnect().
|
inline |
Gets the truncate factor of the turn.
Definition at line 104 of file CServoeNeck.h.
References m_NumPrevAngles.
void CServoeNeck::setOffsets | ( | float | offset0, |
float | offset1, | ||
float | offset2 | ||
) |
Load the Offset values for each servo.
Definition at line 426 of file CServoeNeck.cpp.
References m_offsets.
|
protected |
Definition at line 124 of file CServoeNeck.cpp.
References mrpt::serialization::archiveFrom(), mrpt::comms::CInterfaceFTDI::Close(), mrpt::serialization::CMessage::content, mrpt::comms::CInterfaceFTDI::isOpen(), and mrpt::serialization::CMessage::type.
Referenced by center(), and setAngle().
|
protected |
Definition at line 162 of file CServoeNeck.cpp.
References mrpt::serialization::archiveFrom(), mrpt::comms::CInterfaceFTDI::Close(), mrpt::serialization::CMessage::content, mrpt::comms::CInterfaceFTDI::isOpen(), and mrpt::serialization::CMessage::type.
Referenced by setAngleAndSpeed().
|
inherited |
Change read & write timeouts, in milliseconds.
Definition at line 351 of file CInterfaceFTDI_WIN.cpp.
References ASSERT_, mrpt::comms::CInterfaceFTDI::checkErrorAndRaise(), mrpt::comms::CInterfaceFTDI::m_ftHandle, mrpt::comms::CInterfaceFTDI::m_pSetTimeouts, MRPT_END, and MRPT_START.
Referenced by checkConnectionAndConnect().
|
inline |
Gets the truncate factor of the turn.
Definition at line 96 of file CServoeNeck.h.
References ASSERT_, and m_TruncateFactor.
|
overridevirtualinherited |
Introduces a pure virtual method responsible for writing to the stream.
Write attempts to write up to Count bytes to Buffer, and returns the number of bytes actually written.
Implements mrpt::io::CStream.
Definition at line 54 of file CInterfaceFTDI_common.cpp.
References mrpt::comms::CInterfaceFTDI::ftdi_write().
Referenced by mrpt::comms::CInterfaceFTDI::WriteSync().
|
inlineinherited |
Tries to write, raising no exception if not all the bytes are available, but raising one if there is some communication error.
Definition at line 133 of file CInterfaceFTDI.h.
References mrpt::comms::CInterfaceFTDI::Write().
|
protected |
The value set in the ICR register within the ATMEGA16 controller.
Definition at line 120 of file CServoeNeck.h.
|
protected |
Number of previous angles to store for averaging.
Definition at line 128 of file CServoeNeck.h.
Referenced by getNumberOfPreviousAngles(), setAngleWithFilter(), and setNumberOfPreviousAngles().
|
protected |
The offset used for each servo.
Definition at line 130 of file CServoeNeck.h.
Referenced by center(), CServoeNeck(), setAngle(), setAngleAndSpeed(), and setOffsets().
|
protected |
A vector containing the last N angles which where passed to the servo (for averaging)
Definition at line 126 of file CServoeNeck.h.
Referenced by setAngleWithFilter().
|
protectedinherited |
Used in Read.
Definition at line 175 of file CInterfaceFTDI.h.
Referenced by mrpt::comms::CInterfaceFTDI::Close(), mrpt::comms::CInterfaceFTDI::OpenByDescription(), mrpt::comms::CInterfaceFTDI::OpenBySerialNumber(), mrpt::comms::CInterfaceFTDI::Purge(), mrpt::comms::CInterfaceFTDI::Read(), and mrpt::comms::CInterfaceFTDI::ResetDevice().
|
protected |
The range of turn of the servo will be truncated to "+-m_truncate_factor*(pi/2)".
Definition at line 123 of file CServoeNeck.h.
Referenced by getTruncateFactor(), setAngle(), setAngleAndSpeed(), and setTruncateFactor().
|
protected |
A copy of the device serial number (to open the USB FTDI chip).
Definition at line 118 of file CServoeNeck.h.
Referenced by checkConnectionAndConnect().
Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020 |