A USB-interface for a custom "robotic neck" designed at MAPIR lab.
Definition at line 24 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 () | |
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... | |
virtual size_t | ReadBufferImmediate (void *Buffer, size_t Count) |
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... | |
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... | |
size_t | ReadBuffer (void *Buffer, size_t Count) |
Reads a block of bytes from the stream into Buffer. More... | |
template<typename T > | |
size_t | ReadBufferFixEndianness (T *ptr, size_t ElementCount) |
Reads a sequence of elemental datatypes, taking care of reordering their bytes from the MRPT stream standard (little endianness) to the format of the running architecture. More... | |
void | WriteBuffer (const void *Buffer, size_t Count) |
Writes a block of bytes to the stream from Buffer. More... | |
template<typename T > | |
void | WriteBufferFixEndianness (const T *ptr, size_t ElementCount) |
Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running architecture to MRPT stream standard (little endianness). More... | |
void | WriteObject (const CSerializable *o) |
Writes an object to the stream. More... | |
CSerializablePtr | ReadObject () |
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object. More... | |
void | ReadObject (CSerializable *existingObj) |
Reads an object from stream, where its class must be the same as the supplied object, where the loaded object will be stored in. More... | |
CStream & | operator<< (const CSerializablePtr &pObj) |
Write an object to a stream in the binary MRPT format. More... | |
CStream & | operator<< (const CSerializable &obj) |
Write an object to a stream in the binary MRPT format. More... | |
CStream & | operator>> (CSerializablePtr &pObj) |
CStream & | operator>> (CSerializable &obj) |
template<typename STORED_TYPE , typename CAST_TO_TYPE > | |
void | ReadAsAndCastTo (CAST_TO_TYPE &read_here) |
Read a value from a stream stored in a type different of the target variable, making the conversion via static_cast. 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... | |
void | sendMessage (const utils::CMessage &msg) |
Send a message to the device. More... | |
bool | receiveMessage (utils::CMessage &msg) |
Tries to receive a message from the device. 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) |
size_t | Read (void *Buffer, size_t Count) |
Introduces a pure virtual method responsible for reading from the stream. More... | |
size_t | Write (const void *Buffer, size_t Count) |
Introduces a pure virtual method responsible for writing to the stream. More... | |
uint64_t | Seek (int64_t Offset, CStream::TSeekOrigin Origin=sFromBeginning) |
This virtual method does nothing in this class. More... | |
uint64_t | getTotalBytesCount () |
This virtual method does nothing in this class. More... | |
uint64_t | getPosition () |
This virtual method does nothing in this class. More... | |
void | ftdi_read (void *lpvBuffer, unsigned long dwBuffSize, unsigned long *lpdwBytesRead) |
void | ftdi_write (const void *lpvBuffer, unsigned long dwBuffSize, unsigned long *lpdwBytes) |
void | recursive_fill_list_devices (void *usb_device_structure, TFTDIDeviceList &outList) |
Process recursively a USB device and its children: More... | |
template<bool EXISTING_OBJ> | |
void | internal_ReadObject (CSerializablePtr &newObj, CSerializable *existingObj=NULL) |
A common template code for both versions of CStream::ReadObject() More... | |
Protected Attributes | |
std::string | m_usbSerialNumber |
A copy of the device serial number (to open the USB FTDI chip). More... | |
double | m_MaxValue |
The value set in the ICR register within the ATMEGA16 controller. More... | |
double | m_TruncateFactor |
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 |
Number of previous angles to store for averaging. More... | |
std::vector< float > | m_offsets |
The offset used for each servo. More... | |
mrpt::utils::circular_buffer< uint8_t > | m_readBuffer |
Used in Read. More... | |
void * | m_ftdi_context |
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 |
CServoeNeck::CServoeNeck | ( | ) |
Definition at line 25 of file CServoeNeck.cpp.
References m_offsets.
CServoeNeck::~CServoeNeck | ( | ) |
Definition at line 37 of file CServoeNeck.cpp.
|
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 77 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 366 of file CServoeNeck.cpp.
References angle2RegValue(), m_offsets, and setRegisterValue().
|
private |
Tries to connect to the USB device (if disconnected).
Definition at line 375 of file CServoeNeck.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::hwdrivers::CInterfaceFTDI::isOpen(), m_usbSerialNumber, mrpt::hwdrivers::CInterfaceFTDI::OpenBySerialNumber(), mrpt::hwdrivers::CInterfaceFTDI::Purge(), mrpt::hwdrivers::CInterfaceFTDI::SetLatencyTimer(), mrpt::hwdrivers::CInterfaceFTDI::SetTimeouts(), and mrpt::system::sleep().
Referenced by queryFirmwareVersion().
|
inherited |
Close the USB device.
Referenced by checkConnectionAndConnect(), disableServo(), enableServo(), getRegisterValue(), queryFirmwareVersion(), setRegisterValue(), setRegisterValueAndSpeed(), and mrpt::hwdrivers::CSickLaserUSB::waitContinuousSampleFrame().
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 300 of file CServoeNeck.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::CMessage::content, mrpt::hwdrivers::CInterfaceFTDI::isOpen(), mrpt::utils::CStream::receiveMessage(), mrpt::utils::CStream::sendMessage(), and mrpt::utils::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 333 of file CServoeNeck.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::CMessage::content, mrpt::hwdrivers::CInterfaceFTDI::isOpen(), mrpt::utils::CStream::receiveMessage(), mrpt::utils::CStream::sendMessage(), and mrpt::utils::CMessage::type.
|
protectedinherited |
Referenced by mrpt::hwdrivers::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 223 of file CServoeNeck.cpp.
References getRegisterValue(), and regValue2angle().
|
inherited |
Reads from the stream until a '
' character is found ('' characters are ignored).
Definition at line 680 of file CStream.cpp.
|
inline |
Gets the truncate factor of the turn.
Definition at line 97 of file CServoeNeck.h.
|
protectedvirtualinherited |
This virtual method does nothing in this class.
Implements mrpt::utils::CStream.
Definition at line 84 of file CInterfaceFTDI_common.cpp.
Definition at line 182 of file CServoeNeck.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::CMessage::content, mrpt::hwdrivers::CInterfaceFTDI::isOpen(), mrpt::utils::CStream::receiveMessage(), mrpt::utils::CStream::sendMessage(), and mrpt::utils::CMessage::type.
Referenced by getCurrentAngle().
|
protectedvirtualinherited |
This virtual method does nothing in this class.
Implements mrpt::utils::CStream.
Definition at line 76 of file CInterfaceFTDI_common.cpp.
|
inline |
Gets the truncate factor of the turn.
Definition at line 85 of file CServoeNeck.h.
|
protectedinherited |
A common template code for both versions of CStream::ReadObject()
Definition at line 357 of file CStream.cpp.
References ASSERT_, mrpt::utils::TRuntimeClassId::className, mrpt::utils::TRuntimeClassId::createObject(), mrpt::utils::findRegisteredClass(), mrpt::format(), mrpt::utils::CSerializable::GetRuntimeClass(), mrpt::utils::registerAllPendingClasses(), SERIALIZATION_END_FLAG, THROW_EXCEPTION, THROW_EXCEPTION_FMT, THROW_STACKED_EXCEPTION_CUSTOM_MSG2, THROW_TYPED_EXCEPTION, and version.
|
inherited |
Checks whether the chip has been successfully open.
Referenced by checkConnectionAndConnect(), mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected(), disableServo(), enableServo(), getRegisterValue(), setRegisterValue(), and setRegisterValueAndSpeed().
|
inherited |
Generates a list with all FTDI devices connected right now.
|
inherited |
Open by device description.
|
inherited |
Open by device serial number.
Referenced by checkConnectionAndConnect(), and mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
inherited |
Write an object to a stream in the binary MRPT format.
Definition at line 211 of file CStream.cpp.
|
inherited |
Write an object to a stream in the binary MRPT format.
Definition at line 218 of file CStream.cpp.
|
inherited |
Definition at line 224 of file CStream.cpp.
|
inherited |
Definition at line 230 of file CStream.cpp.
|
virtualinherited |
Writes a string to the stream in a textual form.
Definition at line 507 of file CStream.cpp.
References MRPT_END, MRPT_START, and vsnprintf.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::utils::TMatchingPairList::dumpToFile(), mrpt::obs::gnss::Message_NMEA_GGA::dumpToStream(), mrpt::obs::gnss::Message_TOPCON_PZS::dumpToStream(), mrpt::obs::gnss::Message_TOPCON_SATS::dumpToStream(), mrpt::obs::gnss::Message_NMEA_GLL::dumpToStream(), mrpt::obs::gnss::Message_NMEA_RMC::dumpToStream(), mrpt::obs::CObservationGPS::dumpToStream(), mrpt::obs::gnss::Message_NMEA_VTG::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NMEA_ZDA::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::dumpToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::dumpToStream(), mrpt::slam::TKLDParams::dumpToTextStream(), mrpt::maps::TMetricMapInitializer::dumpToTextStream(), mrpt::slam::CMetricMapBuilderICP::TConfigParams::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::dumpToTextStream(), mrpt::slam::CIncrementalMapPartitioner::TOptions::dumpToTextStream(), mrpt::slam::CICP::TConfigParams::dumpToTextStream(), mrpt::maps::CGasConcentrationGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_FabMap::TOptions::dumpToTextStream(), mrpt::hmtslam::CTopLCDetector_GridMatching::TOptions::dumpToTextStream(), mrpt::slam::CMetricMapBuilderRBPF::TConstructionOptions::dumpToTextStream(), mrpt::graphslam::TUncertaintyPath< GRAPH_T >::dumpToTextStream(), mrpt::vision::CFeatureExtraction::TOptions::dumpToTextStream(), mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::utils::CLoadableOptions::dumpToTextStream(), mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TInsertionOptions::dumpToTextStream(), mrpt::bayes::CParticleFilter::TParticleFilterOptions::dumpToTextStream(), mrpt::slam::CGridMapAligner::TConfigParams::dumpToTextStream(), mrpt::graphslam::TSlidingWindow::dumpToTextStream(), mrpt::maps::CHeightGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM2D::TOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TLikelihoodOptions::dumpToTextStream(), mrpt::maps::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream(), mrpt::maps::CRandomFieldGridMap3D::TInsertionOptions::dumpToTextStream(), mrpt::maps::CBeaconMap::TInsertionOptions::dumpToTextStream(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::deciders::CRangeScanOps< GRAPH_T >::TParams::dumpToTextStream(), mrpt::maps::COctoMapBase< octree_t, octree_node_t >::TLikelihoodOptions::dumpToTextStream(), mrpt::slam::CRangeBearingKFSLAM::TOptions::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::OptimizationParams::dumpToTextStream(), mrpt::maps::CPointsMap::TInsertionOptions::dumpToTextStream(), mrpt::vision::TStereoSystemParams::dumpToTextStream(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::TParams::dumpToTextStream(), mrpt::vision::CFeature::dumpToTextStream(), mrpt::maps::CLandmarksMap::TInsertionOptions::dumpToTextStream(), mrpt::maps::CPointsMap::TLikelihoodOptions::dumpToTextStream(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::GraphVisualizationParams::dumpToTextStream(), mrpt::maps::CColouredPointsMap::TColourOptions::dumpToTextStream(), mrpt::maps::CLandmarksMap::TLikelihoodOptions::dumpToTextStream(), mrpt::maps::TSetOfMetricMapInitializers::dumpToTextStream(), mrpt::vision::TMatchingOptions::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TInsertionOptions::dumpToTextStream(), mrpt::hmtslam::CHMTSLAM::TOptions::dumpToTextStream(), mrpt::maps::COccupancyGridMap2D::TLikelihoodOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLaserParams::dumpToTextStream(), mrpt::vision::TMultiResDescMatchOptions::dumpToTextStream(), mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::TLoopClosureParams::dumpToTextStream(), mrpt::vision::TMultiResDescOptions::dumpToTextStream(), mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CHeightGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition::dumpToTextStream_map_specific(), mrpt::maps::CLandmarksMap::TMapDefinition::dumpToTextStream_map_specific(), mrpt::utils::CLoadableOptions::dumpVar_bool(), mrpt::utils::CLoadableOptions::dumpVar_double(), mrpt::utils::CLoadableOptions::dumpVar_float(), mrpt::utils::CLoadableOptions::dumpVar_int(), mrpt::utils::CLoadableOptions::dumpVar_string(), mrpt::synch::CCriticalSection::enter(), generic_dump_BESTPOS(), generic_dump_MARKTIME(), mrpt::maps::CRandomFieldGridMap2D::TInsertionOptionsCommon::internal_dumpToTextStream_common(), mrpt::synch::CCriticalSection::leave(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetObservationsAndDataAssociation(), mrpt::maps::CRandomFieldGridMap3D::saveAsCSV(), mrpt::poses::CPoseInterpolatorBase< 3 >::saveInterpolatedToTextFile(), mrpt::utils::CTimeLogger::saveToCSVFile(), and mrpt::poses::CPoseInterpolatorBase< 3 >::saveToTextFile().
|
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 208 of file CStream.h.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel().
|
inherited |
Purge the I/O buffers.
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 43 of file CServoeNeck.cpp.
References checkConnectionAndConnect(), mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::CMessage::getContentAsString(), mrpt::utils::CStream::receiveMessage(), mrpt::utils::CStream::sendMessage(), mrpt::system::sleep(), and mrpt::utils::CMessage::type.
|
protectedvirtualinherited |
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::utils::CStream.
Definition at line 20 of file CInterfaceFTDI_common.cpp.
References mrpt::utils::circular_buffer< T >::available(), mrpt::hwdrivers::CInterfaceFTDI::ftdi_read(), mrpt::hwdrivers::CInterfaceFTDI::m_readBuffer, min, mrpt::utils::circular_buffer< T >::pop_many(), mrpt::utils::circular_buffer< T >::push_many(), and mrpt::utils::circular_buffer< T >::size().
|
inlineinherited |
|
inherited |
Reads a block of bytes from the stream into Buffer.
std::exception | On any error, or if ZERO bytes are read. |
Definition at line 45 of file CStream.cpp.
References ASSERT_, and THROW_EXCEPTION.
Referenced by mrpt::hwdrivers::CHokuyoURG::assureBufferHasBytes(), mrpt::compress::zip::compress_gz_data_block(), mrpt::compress::zip::decompress(), mrpt::compress::zip::decompress_gz_file(), mrpt::hwdrivers::CGPSInterface::doProcess(), fill_input_buffer(), mrpt::system::loadBinaryFile(), mrpt::utils::CMemoryStream::loadBufferFromFile(), and mrpt::hwdrivers::CHokuyoURG::purgeBuffers().
|
inlineinherited |
Reads a sequence of elemental datatypes, taking care of reordering their bytes from the MRPT stream standard (little endianness) to the format of the running architecture.
ElementCount | The number of elements (not bytes) to read. |
ptr | A pointer to the first output element in an array (or std::vector<>, etc...). |
std::exception | On any error, or if ZERO bytes are read. |
Definition at line 95 of file CStream.h.
References mrpt::mrpt::utils::reverseBytesInPlace().
Referenced by mrpt::math::operator>>(), and triangle_readFromStream().
|
virtualinherited |
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::utils::CStream.
Definition at line 92 of file CInterfaceFTDI_common.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::ftdi_read().
|
inherited |
Reads an object from stream, its class determined at runtime, and returns a smart pointer to the object.
std::exception | On I/O error or undefined class. |
mrpt::utils::CExceptionEOF | On an End-Of-File condition found at a correct place: an EOF that abruptly finishes in the middle of one object raises a plain std::exception instead. |
Definition at line 486 of file CStream.cpp.
Referenced by mrpt::utils::mrpt_recv_from_zmq(), mrpt::utils::mrpt_recv_from_zmq_into(), mrpt::utils::OctetVectorToObject(), mrpt::nav::CAbstractPTGBasedReactive::performNavigationStep(), mrpt::utils::RawStringToObject(), mrpt::utils::StringToObject(), and TEST().
|
inherited |
Reads an object from stream, where its class must be the same as the supplied object, where the loaded object will be stored in.
std::exception | On I/O error or different class found. |
mrpt::utils::CExceptionEOF | On an End-Of-File condition found at a correct place: an EOF that abruptly finishes in the middle of one object raises a plain std::exception instead. |
Definition at line 498 of file CStream.cpp.
|
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 126 of file CInterfaceFTDI.h.
Referenced by mrpt::hwdrivers::CSickLaserUSB::waitContinuousSampleFrame().
|
inherited |
Tries to receive a message from the device.
std::exception | On communication errors |
Definition at line 590 of file CStream.cpp.
References mrpt::utils::CMessage::content, MAKEWORD16B, mrpt::system::os::memcpy(), MRPT_END, MRPT_START, and mrpt::utils::CMessage::type.
Referenced by disableServo(), enableServo(), mrpt::hwdrivers::CRoboticHeadInterface::Get3SoundBuffer(), mrpt::hwdrivers::CRoboticHeadInterface::GetGain(), mrpt::hwdrivers::CEnoseModular::getObservation(), mrpt::hwdrivers::CBoardENoses::getObservation(), getRegisterValue(), mrpt::hwdrivers::CRoboticHeadInterface::GetSoundLocation(), queryFirmwareVersion(), mrpt::hwdrivers::CBoardENoses::queryFirmwareVersion(), mrpt::hwdrivers::CRoboticHeadInterface::SetGain(), setRegisterValue(), and setRegisterValueAndSpeed().
|
protectedinherited |
Process recursively a USB device and its children:
|
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 91 of file CServoeNeck.cpp.
References M_PI.
Referenced by getCurrentAngle().
|
inherited |
Reset the USB device.
Referenced by mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
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::utils::CClientTCPSocket, mrpt::utils::CFileStream, mrpt::utils::CFileOutputStream, mrpt::utils::CFileGZInputStream, mrpt::utils::CMemoryStream, mrpt::utils::CFileInputStream, and mrpt::utils::CStdOutStream.
|
protectedinherited |
This virtual method does nothing in this class.
Definition at line 66 of file CInterfaceFTDI_common.cpp.
References MRPT_UNUSED_PARAM.
|
inherited |
Send a message to the device.
Note that only the low byte from the "type" field will be used.
For frames of size < 255 the frame format is an array of bytes in this order:
For frames of size > 255 the frame format is an array of bytes in this order:
std::exception | On communication errors |
Definition at line 556 of file CStream.cpp.
References mrpt::utils::CMessage::content, mrpt::system::os::memcpy(), MRPT_END, MRPT_START, and mrpt::utils::CMessage::type.
Referenced by disableServo(), enableServo(), mrpt::hwdrivers::CRoboticHeadInterface::Get3SoundBuffer(), mrpt::hwdrivers::CRoboticHeadInterface::GetGain(), getRegisterValue(), mrpt::hwdrivers::CRoboticHeadInterface::GetSoundLocation(), queryFirmwareVersion(), mrpt::hwdrivers::CBoardENoses::queryFirmwareVersion(), mrpt::hwdrivers::CRoboticHeadInterface::SetGain(), setRegisterValue(), and setRegisterValueAndSpeed().
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 238 of file CServoeNeck.cpp.
References angle2RegValue(), m_offsets, M_PI, m_TruncateFactor, RAD2DEG, and setRegisterValue().
Referenced by setAngleWithFilter().
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 263 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 281 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.
Referenced by checkConnectionAndConnect(), and mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
inline |
Gets the truncate factor of the turn.
Definition at line 93 of file CServoeNeck.h.
void CServoeNeck::setOffsets | ( | float | offset0, |
float | offset1, | ||
float | offset2 | ||
) |
Load the Offset values for each servo.
Definition at line 401 of file CServoeNeck.cpp.
References m_offsets.
|
protected |
Definition at line 105 of file CServoeNeck.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::CMessage::content, mrpt::hwdrivers::CInterfaceFTDI::isOpen(), mrpt::utils::CStream::receiveMessage(), mrpt::utils::CStream::sendMessage(), mrpt::system::sleep(), and mrpt::utils::CMessage::type.
Referenced by center(), and setAngle().
|
protected |
Definition at line 144 of file CServoeNeck.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::Close(), mrpt::utils::CMessage::content, mrpt::hwdrivers::CInterfaceFTDI::isOpen(), mrpt::utils::CStream::receiveMessage(), mrpt::utils::CStream::sendMessage(), mrpt::system::sleep(), and mrpt::utils::CMessage::type.
Referenced by setAngleAndSpeed().
|
inherited |
Change read & write timeouts, in milliseconds.
Referenced by checkConnectionAndConnect(), and mrpt::hwdrivers::CSickLaserUSB::checkControllerIsConnected().
|
inline |
Gets the truncate factor of the turn.
Definition at line 89 of file CServoeNeck.h.
References ASSERT_.
|
protectedvirtualinherited |
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::utils::CStream.
Definition at line 56 of file CInterfaceFTDI_common.cpp.
References mrpt::hwdrivers::CInterfaceFTDI::ftdi_write().
Writes a block of bytes to the stream from Buffer.
std::exception | On any error |
Definition at line 67 of file CStream.cpp.
References ASSERT_, and THROW_EXCEPTION.
Referenced by mrpt::compress::zip::compress(), mrpt::utils::CMessage::deserializeIntoExistingObject(), mrpt::utils::CMessage::deserializeIntoNewObject(), mrpt::hwdrivers::CNTRIPEmitter::doProcess(), mrpt::hwdrivers::CGPSInterface::doProcess(), empty_output_buffer(), mrpt::hwdrivers::CGPSInterface::implement_parser_NOVATEL_OEM6(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::internal_writeToStream(), mrpt::obs::gnss::Message_NV_OEM6_VERSION::internal_writeToStream(), mrpt::utils::mrpt_recv_from_zmq_buf(), mrpt::utils::ObjectToString(), mrpt::hwdrivers::CGPSInterface::OnConnectionEstablished(), mrpt::hwdrivers::CGPSInterface::OnConnectionShutdown(), mrpt::utils::operator<<(), mrpt::utils::CMemoryStream::saveBufferToFile(), mrpt::hwdrivers::CHokuyoURG::sendCmd(), mrpt::hwdrivers::CGPSInterface::sendCustomCommand(), mrpt::hwdrivers::CBoardENoses::setActiveChamber(), mrpt::utils::StringToObject(), term_destination(), mrpt::system::vectorToBinaryFile(), mrpt::nav::CLogFileRecord::writeToStream(), mrpt::maps::CHeightGridMap2D_MRF::writeToStream(), mrpt::maps::CGasConcentrationGridMap2D::writeToStream(), mrpt::maps::CWirelessPowerGridMap2D::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::maps::CReflectivityGridMap2D::writeToStream(), mrpt::obs::CObservationVelodyneScan::writeToStream(), mrpt::maps::COccupancyGridMap2D::writeToStream(), mrpt::maps::CRandomFieldGridMap3D::writeToStream(), mrpt::utils::CImage::writeToStream(), and mrpt::opengl::CRenderizable::writeToStreamRender().
|
inlineinherited |
Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running architecture to MRPT stream standard (little endianness).
ElementCount | The number of elements (not bytes) to write. |
ptr | A pointer to the first input element in an array (or std::vector<>, etc...). Example of usage: |
std::exception | On any error |
Definition at line 139 of file CStream.h.
Referenced by triangle_writeToStream(), mrpt::math::CMatrix::writeToStream(), mrpt::math::CMatrixD::writeToStream(), mrpt::maps::CColouredPointsMap::writeToStream(), mrpt::maps::CWeightedPointsMap::writeToStream(), mrpt::maps::CSimplePointsMap::writeToStream(), mrpt::obs::CObservation2DRangeScan::writeToStream(), mrpt::maps::COccupancyGridMap2D::writeToStream(), and mrpt::obs::CObservation3DRangeScan::writeToStream().
|
inherited |
Writes an object to the stream.
Definition at line 166 of file CStream.cpp.
References ASSERT_, mrpt::utils::TRuntimeClassId::className, mrpt::utils::CSerializable::GetRuntimeClass(), MRPT_END, MRPT_START, SERIALIZATION_END_FLAG, version, and mrpt::utils::CSerializable::writeToStream().
Referenced by mrpt::utils::mrpt_send_to_zmq(), mrpt::utils::ObjectToOctetVector(), mrpt::utils::ObjectToRawString(), mrpt::utils::ObjectToString(), and mrpt::utils::CMessage::serializeObject().
|
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.
|
protectedinherited |
Definition at line 227 of file CInterfaceFTDI.h.
|
protected |
The value set in the ICR register within the ATMEGA16 controller.
Definition at line 105 of file CServoeNeck.h.
|
protected |
Number of previous angles to store for averaging.
Definition at line 108 of file CServoeNeck.h.
Referenced by setAngleWithFilter().
|
protected |
The offset used for each servo.
Definition at line 109 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 107 of file CServoeNeck.h.
Referenced by setAngleWithFilter().
|
protectedinherited |
Used in Read.
Definition at line 150 of file CInterfaceFTDI.h.
Referenced by mrpt::hwdrivers::CInterfaceFTDI::Read().
|
protected |
The range of turn of the servo will be truncated to "+-m_truncate_factor*(pi/2)".
Definition at line 106 of file CServoeNeck.h.
Referenced by setAngle(), and setAngleAndSpeed().
|
protected |
A copy of the device serial number (to open the USB FTDI chip).
Definition at line 104 of file CServoeNeck.h.
Referenced by checkConnectionAndConnect().
Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |