22 #include "../../include/kobuki_driver/kobuki.hpp" 23 #include "../../include/kobuki_driver/packet_handler/payload_headers.hpp" 40 for (
unsigned int i = 2; i < packet_size; i++)
44 return cs ?
false :
true;
52 shutdown_requested(false)
54 , heading_offset(0.0/0.0)
57 , version_info_reminder(0)
58 , controller_info_reminder(0)
59 , velocity_commands_debug(4, 0)
108 sig_warn.
emit(
"device does not (yet) available, is the usb connected?.");
179 ecl::TimeStamp last_signal_time;
181 unsigned char buf[256];
203 sig_info.
emit(
"device does not (yet) available on this port, waiting...");
205 sig_info.
emit(
"device failed to open, waiting... [" + std::string(e.
what()) +
"]");
223 if (
is_alive && ((ecl::TimeStamp() - last_signal_time) > timeout))
228 sig_debug.
emit(
"Timed out while waiting for incoming bytes.");
235 std::ostringstream ostream;
236 ostream <<
"kobuki_node : serial_read(" << n <<
")" 300 if (version_match < 0) {
301 sig_error.
emit(
"This software is incompatible with Kobuki's firmware.");
302 sig_error.
emit(
"You need to upgrade your firmware. For more information,");
303 sig_error.
emit(
"refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
309 else if (version_match > 0) {
310 sig_error.
emit(
"This software is incompatible with Kobuki's firmware.");
311 sig_error.
emit(
"You need to upgrade your software. For more information,");
312 sig_error.
emit(
"refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
322 if (version_match < 0) {
323 sig_warn.
emit(
"The firmware does not match any of the recommended versions for this software.");
324 sig_warn.
emit(
"Consider replacing the firmware. For more information,");
325 sig_warn.
emit(
"refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
329 else if (version_match > 0) {
330 sig_warn.
emit(
"This software is significantly behind the latest firmware.");
331 sig_warn.
emit(
"Please upgrade your software. For more information,");
332 sig_warn.
emit(
"refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
338 catch (std::out_of_range& e)
341 sig_error.
emit(std::string(
"Invalid firmware version number: ").append(e.what()));
368 last_signal_time.stamp();
377 if (
is_alive && ((ecl::TimeStamp() - last_signal_time) > timeout))
389 if (byteStream.
size() < 3 ) {
393 std::stringstream ostream;
394 unsigned int header_id =
static_cast<unsigned int>(byteStream.
pop_front());
395 unsigned int length =
static_cast<unsigned int>(byteStream.
pop_front());
396 unsigned int remains = byteStream.
size();
399 ostream <<
"[" << header_id <<
"]";
400 ostream <<
"[" << length <<
"]";
403 ostream << std::setfill(
'0') << std::uppercase;
404 ostream << std::hex << std::setw(2) << header_id <<
" " << std::dec;
405 ostream << std::hex << std::setw(2) << length <<
" " << std::dec;
407 if (remains < length) to_pop = remains;
408 else to_pop = length;
410 for (
unsigned int i = 0; i < to_pop; i++ ) {
411 unsigned int byte =
static_cast<unsigned int>(byteStream.
pop_front());
412 ostream << std::hex << std::setw(2) << byte <<
" " << std::dec;
416 if (remains < length)
sig_named.
emit(
log(
"error",
"packet",
"malformed sub-payload detected. " + ostream.str()));
417 else sig_named.
emit(
log(
"debug",
"packet",
"unknown sub-payload detected. " + ostream.str()));
453 double &wheel_right_angle_rate)
472 pose_update, pose_update_rates);
503 const unsigned int &i_gain,
const unsigned int &d_gain)
506 sig_warn.
emit(
"Your robot firmware will need to be upgraded to get/set of PID gains." \
507 "Refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
509 +
". You will need at least 1.2.x");
520 sig_warn.
emit(
"Your robot firmware will need to be upgraded to get/set PID gains." \
521 "Refer to https://kobuki.readthedocs.io/en/devel/firmware.html.");
523 +
". You will need at least 1.2.x");
538 std::vector<double> velocity_commands_received;
584 unsigned char checksum = 0;
620 std::cout <<
"========== Void ==========" << std::endl;
622 std::cout <<
"========= String =========" << std::endl;
624 std::cout <<
"====== Button Event ======" << std::endl;
626 std::cout <<
"====== Bumper Event ======" << std::endl;
628 std::cout <<
"====== Cliff Event =======" << std::endl;
630 std::cout <<
"====== Wheel Event =======" << std::endl;
632 std::cout <<
"====== Power Event =======" << std::endl;
634 std::cout <<
"====== Input Event =======" << std::endl;
636 std::cout <<
"====== Robot Event =======" << std::endl;
638 std::cout <<
"====== VersionInfo =======" << std::endl;
640 std::cout <<
"===== Command Buffer =====" << std::endl;
std::vector< std::string > log(std::string msg)
ecl::Signal< PacketFinder::BufferType & > sig_raw_data_stream
struct kobuki::Cliff::Data data
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
ControllerInfo controller_info
AccelerationLimiter acceleration_limiter
void configure(const std::string &sigslots_namespace, const BufferType &putStx, const BufferType &putEtx, unsigned int sizeLengthField, unsigned int sizeMaxPayload, unsigned int sizeChecksumField, bool variableSizePayload)
void sendCommand(Command command)
Send the prepared command to the serial port.
EventManager event_manager
static Command SetControllerGain(const unsigned char &type, const unsigned int &p_gain, const unsigned int &i_gain, const unsigned int &d_gain)
int checkMajorVersion() const
void fixPayload(ecl::PushAndPop< unsigned char > &byteStream)
double battery_low
Threshold for battery level warnings [14.0V].
Command::Buffer command_buffer
bool setControllerGain(const unsigned char &type, const unsigned int &p_gain, const unsigned int &i_gain, const unsigned int &d_gain)
const char * what() const
ecl::Signal< const std::string & > sig_info
int controller_info_reminder
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
unsigned int size() const
bool validate()
A validator to ensure the user has supplied correct/sensible parameter values.
struct kobuki::CoreSensors::Data data
ecl::Signal< const std::vector< short > & > sig_raw_control_command
ecl::PushAndPop< unsigned char > BufferType
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
ecl::Signal< const VersionInfo & > sig_version_info
std::string device_port
The serial device port name [/dev/kobuki].
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
struct kobuki::UniqueDeviceID::Data data
std::vector< uint16_t > bottom
ecl::Signal< const std::string & > sig_error
double battery_dangerous
Threshold for battery level in danger of depletion [13.2V].
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
std::string sigslots_namespace
The first part of a sigslot connection namespace ["/kobuki"].
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
void update(const CoreSensors::Data &new_state, const std::vector< uint16_t > &cliff_data)
struct kobuki::Inertia::Data data
ecl::Signal< const std::string & > sig_debug
void sendBaseControlCommand()
static Command SetLedArray(const enum LedNumber &number, const enum LedColour &colour, Command::Data ¤t_data)
void getBuffer(BufferType &bufferRef)
void setLed(const enum LedNumber &number, const enum LedColour &colour)
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
void push_back(const Type &datum)
static std::string toString(const uint32_t &version)
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
UniqueDeviceID unique_device_id
void setExternalPower(const DigitalOutput &digital_output)
ecl::Angle< double > getHeading() const
ecl::Signal< Command::Buffer & > sig_raw_data_command
void playSoundSequence(const enum SoundSequences &number)
Parameter list and validator for the kobuki.
void init(Parameters ¶meters)
int checkRecommendedVersion() const
double getAngularVelocity() const
std::vector< double > limit(const std::vector< double > &command)
Limits the input velocity commands if gatekeeper is enabled.
void setDigitalOutput(const DigitalOutput &digital_output)
void getWheelJointStates(double &wheel_left_angle, double &wheel_left_angle_rate, double &wheel_right_angle, double &wheel_right_angle_rate)
static Command SetDigitalOutput(const DigitalOutput &digital_output, Command::Data ¤t_data)
int version_info_reminder
void velocityCommands(const double &vx, const double &wz)
static const std::vector< uint32_t > RECOMMENDED_VERSIONS
const uint32_t & version() const
static Command SetVelocityControl(DiffDrive &diff_drive)
static void printStatistics()
ecl_geometry_PUBLIC const float & wrap_angle(float &angle)
void updateOdometry(ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
Use the current sensor data (encoders and gyro) to calculate an update for the odometry.
ThreeAxisGyro three_axis_gyro
void setBaseControl(const double &linear_velocity, const double &angular_velocity)
std::vector< double > pointVelocity() const
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
void resetBuffer(Buffer &buffer)
unsigned int numberOfDataToRead()
bool deserialise(ecl::PushAndPop< unsigned char > &byteStream)
ecl::Signal sig_controller_info
ecl::Signal< const std::string & > sig_warn
void update(const uint16_t &time_stamp, const uint16_t &left_encoder, const uint16_t &right_encoder, ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates)
Updates the odometry from firmware stamps and encoders.
void f(int i) ecl_debug_throw_decl(StandardException)
void connect(const std::string &topic)
void getPayload(BufferType &bufferRef)
double battery_capacity
Capacity voltage of the battery [16.5V].
void printSigSlotConnections() const
Print a list of all relevant sigslot connections.
static Command GetVersionInfo()
bool serialise(ecl::PushAndPop< unsigned char > &byteStream)
virtual bool update(const unsigned char *incoming, unsigned int numberOfIncoming)
ecl::Signal< const std::vector< std::string > & > sig_named
PacketFinder packet_finder
static Command PlaySoundSequence(const enum SoundSequences &number, Command::Data ¤t_data)
void init(const std::string &sigslots_namespace)
static Command GetControllerGain()
struct kobuki::Hardware::Data data
void spin()
Performs a scan looking for incoming data packets.
bool enable_acceleration_limiter
Enable or disable the acceleration limiter [true].
void init(bool enable_acceleration_limiter, double linear_acceleration_max_=0.5, double angular_acceleration_max_=3.5, double linear_deceleration_max_=-0.5 *1.2, double angular_deceleration_max_=-3.5 *1.2)
std::vector< short > velocity_commands_debug
static Command SetExternalPower(const DigitalOutput &digital_output, Command::Data ¤t_data)
void setVelocityCommands(const double &vx, const double &wz)
ecl::Signal sig_stream_data
const ErrorFlag & flag() const
PacketFinder::BufferType data_buffer