MRPT  2.0.0
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions
mrpt::hwdrivers::CServoeNeck Class Referenceabstract

Detailed Description

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>

Inheritance diagram for mrpt::hwdrivers::CServoeNeck:

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

Member Enumeration Documentation

◆ TSeekOrigin

Used in CStream::Seek.

Enumerator
sFromBeginning 
sFromCurrent 
sFromEnd 

Definition at line 32 of file io/CStream.h.

Constructor & Destructor Documentation

◆ CServoeNeck()

CServoeNeck::CServoeNeck ( )

Definition at line 30 of file CServoeNeck.cpp.

References m_offsets.

◆ ~CServoeNeck()

CServoeNeck::~CServoeNeck ( )
overridedefault

Member Function Documentation

◆ angle2RegValue()

unsigned int CServoeNeck::angle2RegValue ( const double  angle)
private

Converts from a decimal angle (in radians) to the corresponding register value for the ATMEGA16 controller (for inner use only).

Parameters
Theangle to convert.
Returns
The value of the register to send.

Definition at line 76 of file CServoeNeck.cpp.

References M_PI.

Referenced by center(), setAngle(), and setAngleAndSpeed().

Here is the caller graph for this function:

◆ center()

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().

Here is the call graph for this function:

◆ checkConnectionAndConnect()

bool CServoeNeck::checkConnectionAndConnect ( )
private

Tries to connect to the USB device (if disconnected).

Returns
True on connection OK, false on error.

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Close()

void CInterfaceFTDI::Close ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ disableServo()

bool CServoeNeck::disableServo ( const uint8_t  servo = 0)

Disables the servo so the neck will be loose.

Parameters
Servothe id of the servo to move (in our ATMEGA16, from 0 to 2).
Returns
Whether or not the procedure succeded.

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.

Here is the call graph for this function:

◆ enableServo()

bool CServoeNeck::enableServo ( const uint8_t  servo = 0)

Enables the servo so the neck will be tight.

Parameters
Servothe id of the servo to move (in our ATMEGA16, from 0 to 2).
Returns
Whether or not the procedure succeded.

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.

Here is the call graph for this function:

◆ ftdi_read()

void CInterfaceFTDI::ftdi_read ( void *  lpvBuffer,
unsigned long  dwBuffSize,
unsigned long *  lpdwBytesRead 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ftdi_write()

void CInterfaceFTDI::ftdi_write ( const void *  lpvBuffer,
unsigned long  dwBuffSize,
unsigned long *  lpdwBytes 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCurrentAngle()

bool CServoeNeck::getCurrentAngle ( double &  angle,
const uint8_t  servo = 0 
)

Gets the current angle of the servo (in radians within (-pi,pi))

Parameters
Angle[OUT] The current angle.
Servo[IN] The id of the servo (in our ATMEGA16, from 0 to 2).
Returns
Whether or not the procedure succeded.

Definition at line 239 of file CServoeNeck.cpp.

References getRegisterValue(), and regValue2angle().

Here is the call graph for this function:

◆ getline()

bool CStream::getline ( std::string &  out_str)
inherited

Reads from the stream until a '
' character is found ('' characters are ignored).

Returns
false on EOF or any other read error.

Definition at line 69 of file CStream.cpp.

◆ getNumberOfPreviousAngles()

unsigned int mrpt::hwdrivers::CServoeNeck::getNumberOfPreviousAngles ( )
inline

Gets the truncate factor of the turn.

Definition at line 111 of file CServoeNeck.h.

References m_NumPrevAngles.

◆ getPosition()

uint64_t CInterfaceFTDI::getPosition ( ) const
overridevirtualinherited

This virtual method does nothing in this class.

Implements mrpt::io::CStream.

Definition at line 67 of file CInterfaceFTDI_common.cpp.

◆ getRegisterValue()

bool CServoeNeck::getRegisterValue ( uint16_t &  value,
const uint8_t  servo = 0 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTotalBytesCount()

uint64_t CInterfaceFTDI::getTotalBytesCount ( ) const
overridevirtualinherited

This virtual method does nothing in this class.

Implements mrpt::io::CStream.

Definition at line 66 of file CInterfaceFTDI_common.cpp.

◆ getTruncateFactor()

double mrpt::hwdrivers::CServoeNeck::getTruncateFactor ( )
inline

Gets the truncate factor of the turn.

Definition at line 93 of file CServoeNeck.h.

References m_TruncateFactor.

◆ isOpen()

bool CInterfaceFTDI::isOpen ( )
inherited

Checks whether the chip has been successfully open.

See also
OpenBySerialNumber, OpenByDescription

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().

Here is the caller graph for this function:

◆ ListAllDevices()

void CInterfaceFTDI::ListAllDevices ( TFTDIDeviceList outList)
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.

Here is the call graph for this function:

◆ OpenByDescription()

void CInterfaceFTDI::OpenByDescription ( const std::string &  description)
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.

Here is the call graph for this function:

◆ OpenBySerialNumber()

void CInterfaceFTDI::OpenBySerialNumber ( const std::string &  serialNumber)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ printf()

int CStream::printf ( const char *  fmt,
  ... 
)
virtualinherited

Writes a string to the stream in a textual form.

See also
CStdOutStream

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ printf_vector()

template<typename CONTAINER_TYPE >
virtual int void mrpt::io::CStream::printf_vector ( const char *  fmt,
const CONTAINER_TYPE &  V,
char  separator = ',' 
)
inlineinherited

Prints a vector in the format [A,B,C,...] using CStream::printf, and the fmt string for each vector element T.

Template Parameters
CONTAINER_TYPEcan 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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Purge()

void CInterfaceFTDI::Purge ( )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ queryFirmwareVersion()

bool CServoeNeck::queryFirmwareVersion ( std::string &  out_firmwareVersion)

Gets the firmware version of the eNeck board.

Parameters
out_firmwareVersion[OUTPUT] A string containing the firmware version.
Returns
Whether or not the procedure succeded.

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.

Here is the call graph for this function:

◆ Read()

size_t CInterfaceFTDI::Read ( void *  Buffer,
size_t  Count 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ReadBufferImmediate()

size_t CInterfaceFTDI::ReadBufferImmediate ( void *  Buffer,
size_t  Count 
)
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().

Exceptions
std::exceptionOn 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().

Here is the call graph for this function:

◆ ReadSync()

size_t mrpt::comms::CInterfaceFTDI::ReadSync ( void *  Buffer,
size_t  Count 
)
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().

Here is the call graph for this function:

◆ regValue2angle()

double CServoeNeck::regValue2angle ( const uint16_t  value)
private

Converts from a certain value of the ATMEGA16 PWM register to the corresponding decimal angle (for inner use only).

Parameters
Thevalue to convert.
Returns
The corresponding angle.

Definition at line 98 of file CServoeNeck.cpp.

References M_PI.

Referenced by getCurrentAngle().

Here is the caller graph for this function:

◆ ResetDevice()

void CInterfaceFTDI::ResetDevice ( )
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.

Here is the call graph for this function:

◆ Seek() [1/2]

virtual uint64_t mrpt::io::CStream::Seek ( int64_t  Offset,
CStream::TSeekOrigin  Origin = sFromBeginning 
)
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:

  • sFromBeginning (Default) Offset is from the beginning of the resource. Seek moves to the position Offset. Offset must be >= 0.
  • sFromCurrent Offset is from the current position in the resource. Seek moves to Position + Offset.
  • sFromEnd Offset is from the end of the resource. Offset must be <= 0 to indicate a number of bytes before the end of the file.
    Returns
    Seek returns the new value of the Position property.

Implemented in mrpt::io::CPipeBaseEndPoint, mrpt::io::CFileStream, mrpt::io::CFileGZInputStream, mrpt::io::CFileGZOutputStream, mrpt::io::CMemoryStream, mrpt::io::CFileOutputStream, and mrpt::io::CFileInputStream.

◆ Seek() [2/2]

uint64_t CInterfaceFTDI::Seek ( int64_t  Offset,
CStream::TSeekOrigin  Origin = sFromBeginning 
)
overrideinherited

This virtual method does nothing in this class.

Definition at line 61 of file CInterfaceFTDI_common.cpp.

◆ setAngle()

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)

Parameters
Anglethe desired angle to turn.
Servothe id of the servo to move (in our ATMEGA16, from 0 to 2).
Fastindicates if the servo must reach the angle at maximum speed
Returns
Whether or not the procedure succeded.

Definition at line 254 of file CServoeNeck.cpp.

References angle2RegValue(), m_offsets, M_PI, m_TruncateFactor, mrpt::RAD2DEG(), and setRegisterValue().

Referenced by setAngleWithFilter().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setAngleAndSpeed()

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)

Parameters
Anglethe desired angle to turn.
Servothe id of the servo to move (in our ATMEGA16, from 0 to 2).
Speedindicates the speed of the servo
Returns
Whether or not the procedure succeded.

Definition at line 284 of file CServoeNeck.cpp.

References angle2RegValue(), m_offsets, M_PI, m_TruncateFactor, and setRegisterValueAndSpeed().

Here is the call graph for this function:

◆ setAngleWithFilter()

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.

Parameters
Anglethe new desired angle to turn.
Servothe id of the servo to move (in our ATMEGA16, from 0 to 2).
Fastindicates if the servo must reach the angle at maximum speed
Returns
Whether or not the procedure succeded.

Definition at line 307 of file CServoeNeck.cpp.

References m_NumPrevAngles, m_PrevAngles, and setAngle().

Here is the call graph for this function:

◆ SetLatencyTimer()

void CInterfaceFTDI::SetLatencyTimer ( unsigned char  latency_ms)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setNumberOfPreviousAngles()

void mrpt::hwdrivers::CServoeNeck::setNumberOfPreviousAngles ( const unsigned int  number)
inline

Gets the truncate factor of the turn.

Definition at line 104 of file CServoeNeck.h.

References m_NumPrevAngles.

◆ setOffsets()

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.

◆ setRegisterValue()

bool CServoeNeck::setRegisterValue ( const uint16_t  value,
const uint8_t  servo = 0,
bool  fast = false 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setRegisterValueAndSpeed()

bool CServoeNeck::setRegisterValueAndSpeed ( const uint16_t  value,
const uint8_t  servo,
const uint16_t  speed 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ SetTimeouts()

void CInterfaceFTDI::SetTimeouts ( unsigned long  dwReadTimeout_ms,
unsigned long  dwWriteTimeout_ms 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setTruncateFactor()

void mrpt::hwdrivers::CServoeNeck::setTruncateFactor ( const double  factor)
inline

Gets the truncate factor of the turn.

Definition at line 96 of file CServoeNeck.h.

References ASSERT_, and m_TruncateFactor.

◆ Write()

size_t CInterfaceFTDI::Write ( const void *  Buffer,
size_t  Count 
)
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ WriteSync()

size_t mrpt::comms::CInterfaceFTDI::WriteSync ( const void *  Buffer,
size_t  Count 
)
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().

Here is the call graph for this function:

Member Data Documentation

◆ m_MaxValue

double mrpt::hwdrivers::CServoeNeck::m_MaxValue {10000}
protected

The value set in the ICR register within the ATMEGA16 controller.

Definition at line 120 of file CServoeNeck.h.

◆ m_NumPrevAngles

unsigned int mrpt::hwdrivers::CServoeNeck::m_NumPrevAngles {5}
protected

Number of previous angles to store for averaging.

Definition at line 128 of file CServoeNeck.h.

Referenced by getNumberOfPreviousAngles(), setAngleWithFilter(), and setNumberOfPreviousAngles().

◆ m_offsets

std::vector<float> mrpt::hwdrivers::CServoeNeck::m_offsets
protected

The offset used for each servo.

Definition at line 130 of file CServoeNeck.h.

Referenced by center(), CServoeNeck(), setAngle(), setAngleAndSpeed(), and setOffsets().

◆ m_PrevAngles

std::deque<double> mrpt::hwdrivers::CServoeNeck::m_PrevAngles
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().

◆ m_readBuffer

mrpt::containers::circular_buffer<uint8_t> mrpt::comms::CInterfaceFTDI::m_readBuffer
protectedinherited

◆ m_TruncateFactor

double mrpt::hwdrivers::CServoeNeck::m_TruncateFactor {0.5}
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().

◆ m_usbSerialNumber

std::string mrpt::hwdrivers::CServoeNeck::m_usbSerialNumber
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.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020