33 CHokuyoURG::CHokuyoURG() :
39 m_highSensMode(false),
44 m_I_am_owner_serial_port(false),
46 m_timeStartSynchDelay(0),
47 m_disable_firmware_timestamp(false),
75 bool &outThereIsObservation,
79 outThereIsObservation =
false;
80 hardwareError =
false;
92 char rcv_status0,rcv_status1;
96 int expectedSize = nRanges*3 + 4;
100 expectedSize += nRanges*3;
111 if (rcv_status0!=
'0' && rcv_status0!=
'9')
113 hardwareError =
true;
122 if ( expectedSize!=rcv_dataLength )
124 MRPT_LOG_DEBUG_FMT(
"[CHokuyoURG::doProcess] ERROR: Expecting %u data bytes, received %u instead!\n",expectedSize,rcv_dataLength);
125 hardwareError =
true;
132 do_timestamp_sync=
false;
136 if (do_timestamp_sync)
140 ((rcv_data[0]-0x30) << 18) +
141 ((rcv_data[1]-0x30) << 12) +
142 ((rcv_data[2]-0x30) << 6) +
168 char *ptr = (
char*) &rcv_data[4];
173 for (
int i=0;i<nRanges;i++)
175 int b1 = (*ptr++)-0x30;
176 int b2 = (*ptr++)-0x30;
177 int b3 = (*ptr++)-0x30;
179 int range_mm = ( (
b1 << 12) | (
b2 << 6) |
b3);
186 int b4 = (*ptr++)-0x30;
187 int b5 = (*ptr++)-0x30;
188 int b6 = (*ptr++)-0x30;
199 outThereIsObservation =
true;
213 configSource.
read_float(iniSection,
"pose_x",0),
214 configSource.
read_float(iniSection,
"pose_y",0),
215 configSource.
read_float(iniSection,
"pose_z",0),
223 #ifdef MRPT_OS_WINDOWS 366 char rcv_status0,rcv_status1;
373 MRPT_LOG_DEBUG(
"[CHokuyoURG::setHighBaudrate] Changing baudrate to 115200...");
382 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
384 std::cerr <<
"Error waiting for response\n";
389 if (rcv_status0!=
'0')
391 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
424 nRead = client->
readAsync( buf, to_read, 100, 10 );
433 catch (std::exception &)
446 const char *sentCmd_forEchoVerification,
454 ASSERT_(sentCmd_forEchoVerification!=NULL);
463 const int verifLen = strlen(sentCmd_forEchoVerification);
477 }
while ( i<verifLen );
491 if (rcv_status1!=0x0A)
509 if (nextChar!=0x0A)
return false;
517 bool lastWasLF=
false;
532 if (i==1 && rcv_data[0]==0x0A)
539 if (rcv_data[i-1]==0x0A)
561 else lastWasLF =
false;
565 catch(std::exception &)
583 char rcv_status0,rcv_status1;
590 MRPT_LOG_DEBUG(
"[CHokuyoURG::enableSCIP20] Changing protocol to SCIP2.0...");
599 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
601 std::cerr <<
"Error waiting for response\n";
607 if (rcv_status0!=
'0')
609 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
624 char rcv_status0,rcv_status1;
631 MRPT_LOG_DEBUG(
"[CHokuyoURG::switchLaserOn] Switching laser ON...");
640 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
642 std::cerr <<
"Error waiting for response\n";
647 if (rcv_status0!=
'0')
649 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
664 char rcv_status0,rcv_status1;
671 MRPT_LOG_DEBUG(
"[CHokuyoURG::switchLaserOff] Switching laser OFF...");
680 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
682 std::cerr <<
"Error waiting for response\n";
687 if (rcv_status0!=
'0')
689 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
703 char rcv_status0,rcv_status1;
713 int motorSpeedCode = (600 - motoSpeed_rpm) / 6;
714 if (motorSpeedCode<0 || motorSpeedCode>10)
716 printf(
"ERROR! Motorspeed must be in the range 540-600 rpm\n");
726 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
728 std::cerr <<
"Error waiting for response\n";
733 if (rcv_status0!=
'0')
735 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
749 char rcv_status0,rcv_status1;
756 MRPT_LOG_DEBUG_FMT(
"[CHokuyoURG::setHighSensitivityMode] Setting HS mode to: %s...", enabled ?
"true":
"false" );
765 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
767 std::cerr <<
"Error waiting for response\n";
772 if (rcv_status0!=
'0')
774 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
797 char rcv_status0,rcv_status1;
804 MRPT_LOG_DEBUG(
"[CHokuyoURG::displayVersionInfo] Asking info...");
813 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
815 std::cerr <<
"Error waiting for response\n";
820 if (rcv_status0!=
'0')
822 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
829 for (
int i=0;i<rcv_dataLength;i++)
831 if (rcv_data[i]==
';')
834 rcv_data[rcv_dataLength]=0;
837 "\n------------- HOKUYO Scanner: Version Information ------\n" 839 "-------------------------------------------------------\n\n",rcv_data);
849 char rcv_status0,rcv_status1;
856 MRPT_LOG_DEBUG(
"[CHokuyoURG::displaySensorInfo] Asking for info...");
865 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
867 std::cerr <<
"Error waiting for response\n";
872 if (rcv_status0!=
'0')
874 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
881 for (
int i=0;i<rcv_dataLength;i++)
883 if (rcv_data[i]==
';')
886 rcv_data[rcv_dataLength]=0;
889 "\n------------- HOKUYO Scanner: Product Information ------\n" 891 "-------------------------------------------------------\n\n",rcv_data);
898 if ( NULL != (ptr=strstr(rcv_data,
"DMAX:")) )
899 out_data->
d_max = 0.001 * atoi( ptr+5 );
900 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find DMAX" << endl;
902 if ( NULL != (ptr=strstr(rcv_data,
"DMIN:")) )
903 out_data->
d_min= 0.001 * atoi( ptr+5 );
904 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find DMIN" << endl;
906 if ( NULL != (ptr=strstr(rcv_data,
"ARES:")) )
908 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find ARES" << endl;
910 if ( NULL != (ptr=strstr(rcv_data,
"SCAN:")) )
912 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find SCAN" << endl;
914 if ( NULL != (ptr=strstr(rcv_data,
"AMIN:")) )
916 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find AMIN" << endl;
917 if ( NULL != (ptr=strstr(rcv_data,
"AMAX:")) )
919 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find AMAX" << endl;
920 if ( NULL != (ptr=strstr(rcv_data,
"AFRT:")) )
922 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find AFRT" << endl;
924 if ( NULL != (ptr=strstr(rcv_data,
"MODL:")) )
929 out_data->
model= aux;
931 else cerr <<
"[CHokuyoURG::displayVersionInfo] Parse error: didn't find AFRT" << endl;
944 char rcv_status0,rcv_status1;
951 MRPT_LOG_DEBUG(
"[CHokuyoURG::startScanningMode] Starting scanning mode...");
965 if (!
receiveResponse( cmd, rcv_status0,rcv_status1, rcv_data, rcv_dataLength ) )
967 std::cerr <<
"Error waiting for response\n";
972 if (rcv_status0!=
'0')
974 std::cerr <<
"Error in LIDAR status: "<< (int)rcv_status0 <<
"\n";
1003 cerr <<
"[CHokuyoURG] Socket connection lost! trying to reconnect..." << endl;
1033 cerr <<
"[CHokuyoURG] Serial port connection lost! Trying to reconnect..." << endl;
1058 THROW_EXCEPTION(
"No stream bound to the laser nor COM serial port or ip and port provided in 'm_com_port','m_ip_dir' and 'm_port_dir'");
1071 cerr <<
"[CHokuyoURG] Cannot connect with the server '" <<
m_com_port <<
"'" << endl;
1090 cerr <<
"[CHokuyoURG] Cannot open serial port '" <<
m_com_port <<
"'" << endl;
1116 cerr <<
"[CHokuyoURG::initialize] Error initializing HOKUYO scanner" << endl;
1147 void *buf = malloc(
sizeof(
uint8_t)*to_read);
1151 if ( nRead != to_read )
1152 THROW_EXCEPTION(
"Error in purge buffers: read and expected number of bytes are different.");
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
void BASE_IMPEXP memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) MRPT_NO_THROWS
An OS and compiler independent version of "memcpy".
size_t ReadBuffer(void *Buffer, size_t Count)
Reads a block of bytes from the stream into Buffer.
int scan_front
First, last, and front step of the scanner angular span.
std::string m_com_port
If set to non-empty, the serial port will be attempted to be opened automatically when this class is ...
uint32_t m_timeStartUI
Time of the first data packet, for synchronization purposes.
virtual ~CHokuyoURG()
Destructor: turns the laser off.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
bool isOpen() const
Returns if port has been correctly open.
std::vector< uint8_t > vector_byte
A communications serial port built as an implementation of a utils::CStream.
utils::CStream * m_stream
The I/O channel (will be NULL if not bound).
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
void setTimeouts(int ReadIntervalTimeout, int ReadTotalTimeoutMultiplier, int ReadTotalTimeoutConstant, int WriteTotalTimeoutMultiplier, int WriteTotalTimeoutConstant)
Changes the timeouts of the port, in milliseconds.
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
bool m_intensity
Get intensity from lidar scan (default: false)
void setScanRange(const size_t i, const float val)
void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection)
See the class documentation at the top for expected parameters.
std::string m_sensorLabel
See CGenericSensor.
size_t available() const
The maximum number of elements that can be written ("push") without rising an overflow error...
#define THROW_EXCEPTION(msg)
#define MRPT_LOG_DEBUG_FMT(_FMT_STRING,...)
double d_max
Min/Max ranges, in meters.
size_t size() const
Return the number of elements available for read ("pop") in the buffer (this is NOT the maximum size ...
void WriteBuffer(const void *Buffer, size_t Count)
Writes a block of bytes to the stream from Buffer.
bool m_I_am_owner_serial_port
bool assureBufferHasBytes(const size_t nDesiredBytes)
Assures a minimum number of bytes in the input buffer, reading from the serial port only if required...
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Contains classes for various device interfaces.
void setScanHasIntensity(bool setHasIntensityFlag)
Marks this scan as having or not intensity data.
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
void filterByExclusionAreas(mrpt::obs::CObservation2DRangeScan &obs) const
Mark as invalid those points which (x,y) coordinates fall within the exclusion polygons.
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
char BASE_IMPEXP * strcpy(char *dest, size_t destSize, const char *source) MRPT_NO_THROWS
An OS-independent version of strcpy.
void filterByExclusionAngles(mrpt::obs::CObservation2DRangeScan &obs) const
Mark as invalid those ranges in a set of forbiden angle ranges.
bool switchLaserOn()
Switchs the laser on.
size_t readAsync(void *Buffer, const size_t Count, const int timeoutStart_ms=-1, const int timeoutBetween_ms=-1)
A method for reading from the socket with an optional timeout.
unsigned int m_port_dir
If set to non-empty and m_ip_dir too, the program will try to connect to a Hokuyo using Ethernet comm...
This class allows loading and storing values and vectors of different types from a configuration text...
std::string m_lastSentMeasCmd
The last sent measurement command (MDXXX), including the last 0x0A.
bool m_disable_firmware_timestamp
float maxRange
The maximum range allowed by the device, in meters (e.g. 80m, 50m,...)
const int MINIMUM_PACKETS_TO_SET_TIMESTAMP_REFERENCE
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
mrpt::gui::CDisplayWindow3DPtr m_win
void BASE_IMPEXP sleep(int time_ms) MRPT_NO_THROWS
An OS-independent method for sending the current thread to "sleep" for a given period of time...
void setConfig(int baudRate, int parity=0, int bits=8, int nStopBits=1, bool enableFlowControl=false)
Changes the configuration of the port.
Used in CHokuyoURG::displayVersionInfo.
bool isConnected()
Returns true if this objects represents a successfully connected socket.
void setScanIntensity(const size_t i, const int val)
bool setIntensityMode(bool enabled)
If true scans will capture intensity.
bool displayVersionInfo()
Ask to the device, and print to the debug stream, details about the firmware version,serial number,...
bool displaySensorInfo(CHokuyoURG::TSensorInfo *out_data=NULL)
Ask to the device, and print to the debug stream, details about the sensor model. ...
This namespace contains representation of robot actions and observations.
#define MRPT_LOG_DEBUG(_STRING)
int m_timeStartSynchDelay
Counter to discard to first few packets before setting the correspondence between device and computer...
bool enableSCIP20()
Enables the SCIP2.0 protocol (this must be called at the very begining!).
void bindIO(mrpt::utils::CStream *streamIO)
Binds the object to a given I/O channel.
mrpt::system::TTimeStamp m_timeStartTT
void loadCommonParams(const mrpt::utils::CConfigFileBase &configSource, const std::string &iniSection)
Should be call by derived classes at "loadConfig" (loads exclusion areas AND exclusion angles)...
GLsizei const GLchar ** string
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
T pop()
Retrieve an element from the buffer.
bool switchLaserOff()
Switchs the laser off.
int m_motorSpeed_rpm
The motor speed (default=600rpm)
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
void purgeBuffers()
Empties the RX buffers of the serial port.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp. Where available, this should contain the accurate satellite-based time...
void connect(const std::string &remotePartAddress, unsigned short remotePartTCPPort, unsigned int timeout_ms=0)
Establishes a connection with a remote part.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
bool startScanningMode()
Start the scanning mode, using parameters stored in the object (loaded from the .ini file) After this...
bool checkCOMisOpen()
Returns true if there is a valid stream bound to the laser scanner, otherwise it first try to open th...
void purgeBuffers()
Purge tx and rx buffers.
size_t getReadPendingBytes()
Return the number of bytes already in the receive queue (they can be read without waiting) ...
void open()
Open the port.
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
bool turnOn()
Enables the scanning mode (which may depend on the specific laser device); this must be called before...
void processPreview(const mrpt::obs::CObservation2DRangeScan &obs)
Must be called inside the capture method to allow optional GUI preview of scans.
bool setMotorSpeed(int motoSpeed_rpm)
Changes the motor speed in rpm's (default 600rpm)
#define MRPT_LOG_INFO_FMT(_FMT_STRING,...)
The namespace for 3D scene representation and rendering.
This software driver implements the protocol SCIP-2.0 for interfacing HOKUYO URG/UTM/UXM/UST laser sc...
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
size_t capacity() const
Return the maximum capacity of the buffer.
void initialize()
Turns the laser on.
void doProcessSimple(bool &outThereIsObservation, mrpt::obs::CObservation2DRangeScan &outObservation, bool &hardwareError)
Specific laser scanner "software drivers" must process here new data from the I/O stream...
bool setHighBaudrate()
Passes to 115200bps bitrate.
poses::CPose3D m_sensorPose
The sensor 6D pose:
int BASE_IMPEXP sprintf(char *buf, size_t bufSize, const char *format,...) MRPT_NO_THROWS MRPT_printf_format_check(3
An OS-independent version of sprintf (Notice the bufSize param, which may be ignored in some compiler...
TSensorInfo m_sensor_info
The information gathered when the laser is first open.
mrpt::system::TTimeStamp BASE_IMPEXP secondsToTimestamp(const double nSeconds)
Transform a time interval (in seconds) into TTimeStamp (e.g.
A TCP socket that can be connected to a TCP server, implementing MRPT's CStream interface for passing...
bool m_highSensMode
High sensitivity [HS] mode (default: false)
std::string model
The sensor model.
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters. Must have same length than validRange.
double m_reduced_fov
Used to reduce artificially the interval of scan ranges.
mrpt::utils::circular_buffer< uint8_t > m_rx_buffer
Auxiliary buffer for readings.
int motor_speed_rpm
Standard motor speed, rpm.
void push_many(T *array_elements, size_t count)
Insert an array of elements in the buffer.
unsigned __int32 uint32_t
bool turnOff()
Disables the scanning mode (this can be used to turn the device in low energy mode, if available)
int m_lastRange
The first and last ranges to consider from the scan.
#define ASSERTMSG_(f, __ERROR_MSG)
bool setHighSensitivityMode(bool enabled)
Changes the high sensitivity mode (HS) (default: false)
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
bool receiveResponse(const char *sentCmd_forEchoVerification, char &rcv_status0, char &rcv_status1, char *rcv_data, int &rcv_dataLength)
Waits for a response from the device.
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
std::string m_ip_dir
If set to non-empty and m_port_dir too, the program will try to connect to a Hokuyo using Ethernet co...
void setScanRangeValidity(const size_t i, const bool val)
int scans_per_360deg
Number of measuremens per 360 degrees.