/*! * \brief write to the chip * \param serial serial port object * \param timeout_mS communications timeout in milliseconds * \return true if successful */ bool SonarChipWrite( SerialPort &serial, unsigned timeout_mS) { sbuf[0] = I2C_CMD; sbuf[1] = 0x40; if ((write_x & 3) == 3) sbuf[2] = 0xfe; else sbuf[2] = 0xff; write_x++; CurrentTransmissionType = TRANSMISSION_CHIP_WRITE; if (serial.Out(sbuf, 3, timeout_mS) > 0) return true; else return false; }
/*! * \brief sets the address of a sensor * \param serial serial port object * \param sensor_address address * \param timeout_mS communications timeout in milliseconds * \return true if successful */ bool SetSensorAddress( SerialPort &serial, unsigned char sensor_address, unsigned timeout_mS) { if ((sensor_address <= 0xfe) && (sensor_address >= 0xe0)) { sbuf[0] = CM01_CMD; sbuf[1] = 0x02; sbuf[2] = sensor_address; sbuf[3] = 0; CurrentTransmissionType = TRANSMISSION_SET_ADDRESS; if (serial.Out(sbuf, 4, timeout_mS) > 0) return true; else return false; } else { ROS_ERROR("SRF08 invalid sensor address: %d", (int)sensor_address); return false; } }
/*! * \brief sends a request to read the time of flight of a previous ping * \param serial serial port object * \param sensor_address address * \param timeout_mS communications timeout in milliseconds * \return true if successful */ bool SonarRead( SerialPort &serial, unsigned char sensor_address, unsigned timeout_mS) { if ((sensor_address <= 0xfe) && (sensor_address >= 0xe0)) { sbuf[0] = I2C_CMD; // send sonar read command sbuf[1] = (unsigned char)(sensor_address+1); sbuf[2] = 0x00; sbuf[3] = 0x04; CurrentTransmissionType = TRANSMISSION_READ; if (serial.Out(sbuf, 4, timeout_mS) > 0) return true; else return false; } else { ROS_ERROR("SRF08 invalid sensor address: %d",(int)sensor_address); return false; } }
/*! * \brief sets the sensor gain * \param serial serial port object * \param sensor_address address * \param timeout_mS communications timeout in milliseconds * \return true if successful */ bool SonarGainLimit( SerialPort &serial, unsigned char sensor_address, unsigned timeout_mS) { if ((sensor_address <= 0xfe) && (sensor_address >=0xe0)) { sbuf[0] = I2C_CMD; // send gain limit sbuf[1] = sensor_address; sbuf[2] = 0x01; sbuf[3] = 0x01; sbuf[4] = 20; CurrentTransmissionType = TRANSMISSION_GAIN; if (serial.Out(sbuf, 5, timeout_mS) > 0) return true; else return false; } else { ROS_ERROR("SRF08 invalid sensor address: %d",(int)sensor_address); return false; } }
/*! * \brief sends out a ping * \param serial serial port object * \param sensor_address address * \param timeout_mS communications timeout in milliseconds * \return true if successful */ bool SonarPing( SerialPort &serial, unsigned char sensor_address, unsigned timeout_mS) { if ((sensor_address <= 0xfe) && (sensor_address >=0xe0)) { sbuf[0] = I2C_CMD; // send sonar rangeing (uS) command sbuf[1] = sensor_address; sbuf[2] = 0x00; sbuf[3] = 0x01; sbuf[4] = 0x52; CurrentTransmissionType = TRANSMISSION_PING; if (serial.Out(sbuf, 5, timeout_mS) > 0) return true; else return false; } else { ROS_ERROR("SRF08 invalid sensor address: %d",(int)sensor_address); return false; } }