diff --git a/vesc_driver/CMakeLists.txt b/vesc_driver/CMakeLists.txt index be20368..d0786ab 100644 --- a/vesc_driver/CMakeLists.txt +++ b/vesc_driver/CMakeLists.txt @@ -5,12 +5,14 @@ find_package(catkin REQUIRED COMPONENTS nodelet pluginlib roscpp + std_msgs vesc_msgs + serial ) catkin_package( -# INCLUDE_DIRS include - CATKIN_DEPENDS nodelet pluginlib roscpp vesc_msgs + INCLUDE_DIRS include + CATKIN_DEPENDS nodelet pluginlib roscpp std_msgs vesc_msgs serial ) ########### @@ -18,18 +20,27 @@ catkin_package( ########### include_directories( + include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS} ) # node executable -add_executable(vesc_driver_node src/vesc_driver_node.cpp src/vesc_driver.cpp) +add_executable(vesc_driver_node src/vesc_driver_node.cpp + src/vesc_driver.cpp + src/vesc_interface.cpp + src/vesc_packet.cpp + src/vesc_packet_factory.cpp) target_link_libraries(vesc_driver_node ${catkin_LIBRARIES} ) # nodelet library -add_library(vesc_driver_nodelet src/vesc_driver_nodelet.cpp src/vesc_driver.cpp) +add_library(vesc_driver_nodelet src/vesc_driver_nodelet.cpp + src/vesc_driver.cpp + src/vesc_interface.cpp + src/vesc_packet.cpp + src/vesc_packet_factory.cpp) target_link_libraries(vesc_driver_nodelet ${catkin_LIBRARIES} ) diff --git a/vesc_driver/include/vesc_driver/datatypes.h b/vesc_driver/include/vesc_driver/datatypes.h new file mode 100644 index 0000000..d71df93 --- /dev/null +++ b/vesc_driver/include/vesc_driver/datatypes.h @@ -0,0 +1,371 @@ +/* + Copyright 2012-2014 Benjamin Vedder benjamin@vedder.se + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * datatypes.h + * + * Created on: 14 sep 2014 + * Author: benjamin + */ + +#ifndef DATATYPES_H_ +#define DATATYPES_H_ + +#include +#include +//#include "ch.h" +typedef uint32_t systime_t; // defined in ch.h + +// Data types +typedef enum { + MC_STATE_OFF = 0, + MC_STATE_DETECTING, + MC_STATE_RUNNING, + MC_STATE_FULL_BRAKE, +} mc_state; + +typedef enum { + PWM_MODE_NONSYNCHRONOUS_HISW = 0, // This mode is not recommended + PWM_MODE_SYNCHRONOUS, // The recommended and most tested mode + PWM_MODE_BIPOLAR // Some glitches occasionally, can kill MOSFETs +} mc_pwm_mode; + +typedef enum { + COMM_MODE_INTEGRATE = 0, + COMM_MODE_DELAY +} mc_comm_mode; + +typedef enum { + SENSOR_MODE_SENSORLESS = 0, + SENSOR_MODE_SENSORED, + SENSOR_MODE_HYBRID +} mc_sensor_mode; + +typedef enum { + MOTOR_TYPE_BLDC = 0, + MOTOR_TYPE_DC, +} mc_motor_type; + +typedef enum { + FAULT_CODE_NONE = 0, + FAULT_CODE_OVER_VOLTAGE, + FAULT_CODE_UNDER_VOLTAGE, + FAULT_CODE_DRV8302, + FAULT_CODE_ABS_OVER_CURRENT, + FAULT_CODE_OVER_TEMP_FET, + FAULT_CODE_OVER_TEMP_MOTOR +} mc_fault_code; + +typedef enum { + CONTROL_MODE_DUTY = 0, + CONTROL_MODE_SPEED, + CONTROL_MODE_CURRENT, + CONTROL_MODE_CURRENT_BRAKE, + CONTROL_MODE_POS, + CONTROL_MODE_NONE +} mc_control_mode; + +typedef struct { + float cycle_int_limit; + float cycle_int_limit_running; + float cycle_int_limit_max; + float comm_time_sum; + float comm_time_sum_min_rpm; + int32_t comms; + uint32_t time_at_comm; +} mc_rpm_dep_struct; + +typedef struct { + // Switching and drive + mc_pwm_mode pwm_mode; + mc_comm_mode comm_mode; + mc_motor_type motor_type; + mc_sensor_mode sensor_mode; + // Limits + float l_current_max; + float l_current_min; + float l_in_current_max; + float l_in_current_min; + float l_abs_current_max; + float l_min_erpm; + float l_max_erpm; + float l_max_erpm_fbrake; + float l_max_erpm_fbrake_cc; + float l_min_vin; + float l_max_vin; + bool l_slow_abs_current; + bool l_rpm_lim_neg_torque; + float l_temp_fet_start; + float l_temp_fet_end; + float l_temp_motor_start; + float l_temp_motor_end; + float l_min_duty; + float l_max_duty; + // Overridden limits (Computed during runtime) + float lo_current_max; + float lo_current_min; + float lo_in_current_max; + float lo_in_current_min; + // Sensorless + float sl_min_erpm; + float sl_min_erpm_cycle_int_limit; + float sl_max_fullbreak_current_dir_change; + float sl_cycle_int_limit; + float sl_phase_advance_at_br; + float sl_cycle_int_rpm_br; + float sl_bemf_coupling_k; + // Hall sensor + int8_t hall_table[8]; + float hall_sl_erpm; + // Speed PID + float s_pid_kp; + float s_pid_ki; + float s_pid_kd; + float s_pid_min_rpm; + // Pos PID + float p_pid_kp; + float p_pid_ki; + float p_pid_kd; + // Current controller + float cc_startup_boost_duty; + float cc_min_current; + float cc_gain; + float cc_ramp_step_max; + // Misc + int32_t m_fault_stop_time_ms; +} mc_configuration; + +// Applications to use +typedef enum { + APP_NONE = 0, + APP_PPM, + APP_ADC, + APP_UART, + APP_PPM_UART, + APP_ADC_UART, + APP_NUNCHUK, + APP_NRF, + APP_CUSTOM +} app_use; + +// PPM control types +typedef enum { + PPM_CTRL_TYPE_NONE = 0, + PPM_CTRL_TYPE_CURRENT, + PPM_CTRL_TYPE_CURRENT_NOREV, + PPM_CTRL_TYPE_CURRENT_NOREV_BRAKE, + PPM_CTRL_TYPE_DUTY, + PPM_CTRL_TYPE_DUTY_NOREV, + PPM_CTRL_TYPE_PID, + PPM_CTRL_TYPE_PID_NOREV +} ppm_control_type; + +typedef struct { + ppm_control_type ctrl_type; + float pid_max_erpm; + float hyst; + float pulse_start; + float pulse_end; + bool median_filter; + bool safe_start; + float rpm_lim_start; + float rpm_lim_end; + bool multi_esc; + bool tc; + float tc_max_diff; +} ppm_config; + +// ADC control types +typedef enum { + ADC_CTRL_TYPE_NONE = 0, + ADC_CTRL_TYPE_CURRENT, + ADC_CTRL_TYPE_CURRENT_REV_CENTER, + ADC_CTRL_TYPE_CURRENT_REV_BUTTON, + ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_CENTER, + ADC_CTRL_TYPE_CURRENT_NOREV_BRAKE_BUTTON, + ADC_CTRL_TYPE_DUTY, + ADC_CTRL_TYPE_DUTY_REV_CENTER, + ADC_CTRL_TYPE_DUTY_REV_BUTTON +} adc_control_type; + +typedef struct { + adc_control_type ctrl_type; + float hyst; + float voltage_start; + float voltage_end; + bool use_filter; + bool safe_start; + bool button_inverted; + bool voltage_inverted; + float rpm_lim_start; + float rpm_lim_end; + bool multi_esc; + bool tc; + float tc_max_diff; + uint32_t update_rate_hz; +} adc_config; + +// Nunchuk control types +typedef enum { + CHUK_CTRL_TYPE_NONE = 0, + CHUK_CTRL_TYPE_CURRENT, + CHUK_CTRL_TYPE_CURRENT_NOREV +} chuk_control_type; + +typedef struct { + chuk_control_type ctrl_type; + float hyst; + float rpm_lim_start; + float rpm_lim_end; + float ramp_time_pos; + float ramp_time_neg; + bool multi_esc; + bool tc; + float tc_max_diff; +} chuk_config; + +typedef struct { + // Settings + uint8_t controller_id; + uint32_t timeout_msec; + float timeout_brake_current; + bool send_can_status; + uint32_t send_can_status_rate_hz; + + // Application to use + app_use app_to_use; + + // PPM application settings + ppm_config app_ppm_conf; + + // ADC application settings + adc_config app_adc_conf; + + // UART application settings + uint32_t app_uart_baudrate; + + // Nunchuk application settings + chuk_config app_chuk_conf; +} app_configuration; + +// Communication commands +typedef enum { + COMM_FW_VERSION = 0, + COMM_JUMP_TO_BOOTLOADER, + COMM_ERASE_NEW_APP, + COMM_WRITE_NEW_APP_DATA, + COMM_GET_VALUES, + COMM_SET_DUTY, + COMM_SET_CURRENT, + COMM_SET_CURRENT_BRAKE, + COMM_SET_RPM, + COMM_SET_POS, + COMM_SET_DETECT, + COMM_SET_SERVO_POS, + COMM_SET_MCCONF, + COMM_GET_MCCONF, + COMM_SET_APPCONF, + COMM_GET_APPCONF, + COMM_SAMPLE_PRINT, + COMM_TERMINAL_CMD, + COMM_PRINT, + COMM_ROTOR_POSITION, + COMM_EXPERIMENT_SAMPLE, + COMM_DETECT_MOTOR_PARAM, + COMM_REBOOT, + COMM_ALIVE, + COMM_GET_DECODED_PPM, + COMM_GET_DECODED_ADC, + COMM_GET_DECODED_CHUK, + COMM_FORWARD_CAN +} COMM_PACKET_ID; + +// CAN commands +typedef enum { + CAN_PACKET_SET_DUTY = 0, + CAN_PACKET_SET_CURRENT, + CAN_PACKET_SET_CURRENT_BRAKE, + CAN_PACKET_SET_RPM, + CAN_PACKET_SET_POS, + CAN_PACKET_FILL_RX_BUFFER, + CAN_PACKET_FILL_RX_BUFFER_LONG, + CAN_PACKET_PROCESS_RX_BUFFER, + CAN_PACKET_PROCESS_SHORT_BUFFER, + CAN_PACKET_STATUS +} CAN_PACKET_ID; + +// Logged fault data +typedef struct { + mc_fault_code fault; + float current; + float current_filtered; + float voltage; + float duty; + float rpm; + int tacho; + int tim_pwm_cnt; + int tim_samp_cnt; + int comm_step; + float temperature; +} fault_data; + +// External LED state +typedef enum { + LED_EXT_OFF = 0, + LED_EXT_NORMAL, + LED_EXT_BRAKE, + LED_EXT_TURN_LEFT, + LED_EXT_TURN_RIGHT, + LED_EXT_BRAKE_TURN_LEFT, + LED_EXT_BRAKE_TURN_RIGHT, + LED_EXT_BATT +} LED_EXT_STATE; + +typedef struct { + int js_x; + int js_y; + int acc_x; + int acc_y; + int acc_z; + bool bt_c; + bool bt_z; +} chuck_data; + +typedef struct { + int id; + systime_t rx_time; + float rpm; + float current; + float duty; +} can_status_msg; + +typedef struct { + uint8_t js_x; + uint8_t js_y; + bool bt_c; + bool bt_z; + bool bt_push; + float vbat; +} mote_state; + +typedef enum { + MOTE_PACKET_BATT_LEVEL = 0, + MOTE_PACKET_BUTTONS, + MOTE_PACKET_ALIVE +} MOTE_PACKET; + +#endif /* DATATYPES_H_ */ diff --git a/vesc_driver/include/vesc_driver/v8stdint.h b/vesc_driver/include/vesc_driver/v8stdint.h new file mode 100644 index 0000000..f3be96b --- /dev/null +++ b/vesc_driver/include/vesc_driver/v8stdint.h @@ -0,0 +1,57 @@ +// This header is from the v8 google project: +// http://code.google.com/p/v8/source/browse/trunk/include/v8stdint.h + +// Copyright 2012 the V8 project authors. All rights reserved. +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following +// disclaimer in the documentation and/or other materials provided +// with the distribution. +// * Neither the name of Google Inc. nor the names of its +// contributors may be used to endorse or promote products derived +// from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +// Load definitions of standard types. + +#ifndef V8STDINT_H_ +#define V8STDINT_H_ + +#include +#include + +#if defined(_WIN32) && !defined(__MINGW32__) + +typedef signed char int8_t; +typedef unsigned char uint8_t; +typedef short int16_t; // NOLINT +typedef unsigned short uint16_t; // NOLINT +typedef int int32_t; +typedef unsigned int uint32_t; +typedef __int64 int64_t; +typedef unsigned __int64 uint64_t; +// intptr_t and friends are defined in crtdefs.h through stdio.h. + +#else + +#include + +#endif + +#endif // V8STDINT_H_ diff --git a/vesc_driver/include/vesc_driver/vesc_driver.h b/vesc_driver/include/vesc_driver/vesc_driver.h new file mode 100644 index 0000000..2b7f6dc --- /dev/null +++ b/vesc_driver/include/vesc_driver/vesc_driver.h @@ -0,0 +1,63 @@ +// -*- mode:c++; fill-column: 100; -*- + +#ifndef VESC_DRIVER_VESC_DRIVER_H_ +#define VESC_DRIVER_VESC_DRIVER_H_ + +#include + +#include +#include + +#include "vesc_driver/vesc_interface.h" +#include "vesc_driver/vesc_packet.h" + +namespace vesc_driver +{ + +class VescDriver +{ +public: + + VescDriver(ros::NodeHandle nh, + ros::NodeHandle private_nh); + +private: + // interface to the VESC + VescInterface vesc_; + void vescPacketCallback(const boost::shared_ptr& packet); + void vescErrorCallback(const std::string& error); + + // ROS services + ros::Publisher state_pub_; + ros::Subscriber duty_cycle_sub_; + ros::Subscriber current_sub_; + ros::Subscriber brake_sub_; + ros::Subscriber speed_sub_; + ros::Subscriber position_sub_; + ros::Subscriber servo_sub_; + ros::Timer timer_; + + // driver modes (possible states) + typedef enum { + MODE_INITIALIZING, + MODE_OPERATING + } driver_mode_t; + + // other variables + driver_mode_t driver_mode_; ///< driver state machine mode (state) + int fw_version_major_; ///< firmware major version reported by vesc + int fw_version_minor_; ///< firmware minor version reported by vesc + + // ROS callbacks + void timerCallback(const ros::TimerEvent& event); + void dutyCycleCallback(const std_msgs::Float64::ConstPtr& duty_cycle); + void currentCallback(const std_msgs::Float64::ConstPtr& current); + void brakeCallback(const std_msgs::Float64::ConstPtr& brake); + void speedCallback(const std_msgs::Float64::ConstPtr& speed); + void positionCallback(const std_msgs::Float64::ConstPtr& position); + void servoCallback(const std_msgs::Float64::ConstPtr& servo); +}; + +} // namespace vesc_driver + +#endif // VESC_DRIVER_VESC_DRIVER_H_ diff --git a/vesc_driver/include/vesc_driver/vesc_interface.h b/vesc_driver/include/vesc_driver/vesc_interface.h new file mode 100644 index 0000000..3bc50d0 --- /dev/null +++ b/vesc_driver/include/vesc_driver/vesc_interface.h @@ -0,0 +1,122 @@ +// -*- mode:c++; fill-column: 100; -*- + +#ifndef VESC_DRIVER_VESC_INTERFACE_H_ +#define VESC_DRIVER_VESC_INTERFACE_H_ + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "vesc_driver/vesc_packet.h" + +namespace vesc_driver +{ + +/** + * Class providing an interface to the Vedder VESC motor controller via a serial port interface. + */ +class VescInterface : private boost::noncopyable +{ +public: + + typedef boost::function PacketHandlerFunction; + typedef boost::function ErrorHandlerFunction; + + /** + * Creates a VescInterface object. Opens the serial port interface to the VESC if @p port is not + * empty, otherwise the serial port remains closed until connect() is called. + * + * @param port Address of the serial port, e.g. '/dev/ttyUSB0'. + * @param packet_handler Function this class calls when a VESC packet is received. + * @param error_handler Function this class calls when an error is detected, such as a bad + * checksum. + * + * @throw SerialException + */ + VescInterface(const std::string& port = std::string(), + const PacketHandlerFunction& packet_handler = PacketHandlerFunction(), + const ErrorHandlerFunction& error_handler = ErrorHandlerFunction()); + + /** + * VescInterface destructor. + */ + ~VescInterface(); + + /** + * Sets / updates the function that this class calls when a VESC packet is received. + */ + void setPacketHandler(const PacketHandlerFunction& handler); + + /** + * Sets / updates the function that this class calls when an error is detected, such as a bad + * checksum. + */ + void setErrorHandler(const ErrorHandlerFunction& handler); + + /** + * Opens the serial port interface to the VESC. + * + * @throw SerialException + */ + void connect(const std::string& port); + + /** + * Closes the serial port interface to the VESC. + */ + void disconnect(); + + /** + * Gets the status of the serial interface to the VESC. + * + * @return Returns true if the serial port is open, false otherwise. + */ + bool isConnected() const; + + /** + * Send a VESC packet. + */ + void send(const VescPacket& packet); + + void requestFWVersion(); + void requestState(); + void setDutyCycle(double duty_cycle); + void setCurrent(double current); + void setBrake(double brake); + void setSpeed(double speed); + void setPosition(double position); + void setServo(double servo); + +private: + // Pimpl - hide serial port members from class users + class Impl; + boost::scoped_ptr impl_; +}; + +// todo: review +class SerialException : public std::exception +{ + // Disable copy constructors + SerialException& operator=(const SerialException&); + std::string e_what_; +public: + SerialException (const char *description) { + std::stringstream ss; + ss << "SerialException " << description << " failed."; + e_what_ = ss.str(); + } + SerialException (const SerialException& other) : e_what_(other.e_what_) {} + virtual ~SerialException() throw() {} + virtual const char* what () const throw () { + return e_what_.c_str(); + } +}; + +} // namespace vesc_driver + +#endif // VESC_DRIVER_VESC_INTERFACE_H_ diff --git a/vesc_driver/include/vesc_driver/vesc_packet.h b/vesc_driver/include/vesc_driver/vesc_packet.h new file mode 100644 index 0000000..630634e --- /dev/null +++ b/vesc_driver/include/vesc_driver/vesc_packet.h @@ -0,0 +1,194 @@ +// -*- mode:c++; fill-column: 100; -*- + +#ifndef VESC_DRIVER_VESC_PACKET_H_ +#define VESC_DRIVER_VESC_PACKET_H_ + +#include +#include +#include + +#include +#include + +#include "vesc_driver/v8stdint.h" + +namespace vesc_driver +{ + +typedef std::vector Buffer; +typedef std::pair BufferRange; +typedef std::pair BufferRangeConst; + +/** The raw frame for communicating with the VESC */ +class VescFrame +{ +public: + virtual ~VescFrame() {} + + // getters + virtual const Buffer& frame() const {return *frame_;} + + // VESC packet properties + static const int VESC_MAX_PAYLOAD_SIZE = 1024; ///< Maximum VESC payload size, in bytes + static const int VESC_MIN_FRAME_SIZE = 5; ///< Smallest VESC frame size, in bytes + static const int VESC_MAX_FRAME_SIZE = 6 + VESC_MAX_PAYLOAD_SIZE; ///< Largest VESC frame size, in bytes + static const unsigned int VESC_SOF_VAL_SMALL_FRAME = 2; ///< VESC start of "small" frame value + static const unsigned int VESC_SOF_VAL_LARGE_FRAME = 3; ///< VESC start of "large" frame value + static const unsigned int VESC_EOF_VAL = 3; ///< VESC end-of-frame value + + /** CRC parameters for the VESC */ + typedef boost::crc_optimal<16, 0x1021, 0, 0, false, false> CRC; + +protected: + /** Construct frame with specified payload size. */ + VescFrame(int payload_size); + + boost::shared_ptr frame_; ///< Stores frame data, shared_ptr for shallow copy + BufferRange payload_; ///< View into frame's payload section + +private: + /** Construct from buffer. Used by VescPacketFactory factory. */ + VescFrame(const BufferRangeConst& frame, const BufferRangeConst& payload); + + /** Give VescPacketFactory access to private constructor. */ + friend class VescPacketFactory; +}; + +/*------------------------------------------------------------------------------------------------*/ + +/** A VescPacket is a VescFrame with a non-zero length payload */ +class VescPacket : public VescFrame +{ +public: + virtual ~VescPacket() {} + + virtual const std::string& name() const {return name_;} + +protected: + VescPacket(const std::string& name, int payload_size, int payload_id); + VescPacket(const std::string& name, boost::shared_ptr raw); + +private: + std::string name_; +}; + +typedef boost::shared_ptr VescPacketPtr; +typedef boost::shared_ptr VescPacketConstPtr; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketFWVersion : public VescPacket +{ +public: + VescPacketFWVersion(boost::shared_ptr raw); + + int fwMajor() const; + int fwMinor() const; + +}; + +class VescPacketRequestFWVersion : public VescPacket +{ +public: + VescPacketRequestFWVersion(); + +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketValues : public VescPacket +{ +public: + VescPacketValues(boost::shared_ptr raw); + + double v_in() const; + double temp_mos1() const; + double temp_mos2() const; + double temp_mos3() const; + double temp_mos4() const; + double temp_mos5() const; + double temp_mos6() const; + double temp_pcb() const; + double current_motor() const; + double current_in() const; + double rpm() const; + double duty_now() const; + double amp_hours() const; + double amp_hours_charged() const; + double watt_hours() const; + double watt_hours_charged() const; + double tachometer() const; + double tachometer_abs() const; + int fault_code() const; + +}; + +class VescPacketRequestValues : public VescPacket +{ +public: + VescPacketRequestValues(); +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketSetDuty : public VescPacket +{ +public: + VescPacketSetDuty(double duty); + + // double duty() const; +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketSetCurrent : public VescPacket +{ +public: + VescPacketSetCurrent(double current); + + // double current() const; +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketSetCurrentBrake : public VescPacket +{ +public: + VescPacketSetCurrentBrake(double current_brake); + + // double current_brake() const; +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketSetRPM : public VescPacket +{ +public: + VescPacketSetRPM(double rpm); + + // double rpm() const; +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketSetPos : public VescPacket +{ +public: + VescPacketSetPos(double pos); + + // double pos() const; +}; + +/*------------------------------------------------------------------------------------------------*/ + +class VescPacketSetServoPos : public VescPacket +{ +public: + VescPacketSetServoPos(double servo_pos); + + // double servo_pos() const; +}; + +} // namespace vesc_driver + +#endif // VESC_DRIVER_VESC_PACKET_H_ diff --git a/vesc_driver/include/vesc_driver/vesc_packet_factory.h b/vesc_driver/include/vesc_driver/vesc_packet_factory.h new file mode 100644 index 0000000..f856f44 --- /dev/null +++ b/vesc_driver/include/vesc_driver/vesc_packet_factory.h @@ -0,0 +1,82 @@ +// -*- mode:c++; fill-column: 100; -*- + +#ifndef VESC_DRIVER_VESC_PACKET_FACTORY_H_ +#define VESC_DRIVER_VESC_PACKET_FACTORY_H_ + +#include +#include +#include + +#include +#include +#include + +#include "vesc_driver/v8stdint.h" +#include "vesc_driver/vesc_packet.h" + +namespace vesc_driver +{ + +/** + * Class for creating VESC packets from raw data. + */ +class VescPacketFactory : private boost::noncopyable +{ +public: + /** Return the global factory object */ + static VescPacketFactory* getFactory(); + + /** + * Create a VescPacket from a buffer (factory function). Packet must start (start of frame + * character) at @p begin and complete (end of frame character) before *p end. The buffer element + * at @p end is not examined, i.e. it can be the past-the-end element. Only returns a packet if + * the packet is valid, i.e. valid size, matching checksum, complete etc. An empty pointer is + * returned if a packet cannot be found or if it is invalid. If a valid packet is not found, + * optional output parameter @what is set to a string providing a reason why a packet was not + * found. If a packet was not found because additional bytes are needed on the buffer, optional + * output parameter @p num_bytes_needed will contain the number of bytes needed to either + * determine the size of the packet or complete the packet. Output parameters @p num_bytes_needed + * and @p what will be set to 0 and empty if a valid packet is found. + * + * @param begin[in] Iterator to a buffer at the start-of-frame character + * @param end[in] Iterator to the buffer past-the-end element. + * @param num_bytes_needed[out] Number of bytes needed to determine the packet size or complete + * the frame. + * @param what[out] Human readable string giving a reason why the packet was not found. + * + * @return Pointer to a valid VescPacket if successful. Otherwise, an empty pointer. + */ + static VescPacketPtr createPacket(const Buffer::const_iterator& begin, + const Buffer::const_iterator& end, + int* num_bytes_needed, std::string* what); + + typedef boost::function)> CreateFn; + + /** Register a packet type with the factory. */ + static void registerPacketType(int payload_id, CreateFn fn); + +private: + + typedef std::map FactoryMap; + static FactoryMap* getMap(); +}; + +/** Use this macro to register packets */ +#define REGISTER_PACKET_TYPE(id, klass) \ +class klass##Factory \ +{ \ +public: \ + klass##Factory() \ + { \ + VescPacketFactory::registerPacketType((id), &klass##Factory::create); \ + } \ + static VescPacketPtr create(boost::shared_ptr frame) \ + { \ + return VescPacketPtr(new klass(frame)); \ + } \ +}; \ +static klass##Factory global_##klass##Factory; + +} // namespace vesc_driver + +#endif // VESC_DRIVER_VESC_PACKET_FACTORY_H_ diff --git a/vesc_driver/launch/vesc_driver_node.launch b/vesc_driver/launch/vesc_driver_node.launch index 2442036..0f67076 100644 --- a/vesc_driver/launch/vesc_driver_node.launch +++ b/vesc_driver/launch/vesc_driver_node.launch @@ -6,9 +6,13 @@ + + + - + + diff --git a/vesc_driver/launch/vesc_driver_nodelet.launch b/vesc_driver/launch/vesc_driver_nodelet.launch index 90f790c..bf7bae4 100644 --- a/vesc_driver/launch/vesc_driver_nodelet.launch +++ b/vesc_driver/launch/vesc_driver_nodelet.launch @@ -10,6 +10,9 @@ + + + @@ -24,6 +27,7 @@ + diff --git a/vesc_driver/package.xml b/vesc_driver/package.xml index 9525d1f..2ed45e3 100644 --- a/vesc_driver/package.xml +++ b/vesc_driver/package.xml @@ -19,12 +19,16 @@ nodelet pluginlib roscpp + std_msgs vesc_msgs + serial nodelet pluginlib roscpp + std_msgs vesc_msgs + serial diff --git a/vesc_driver/src/vesc_driver.cpp b/vesc_driver/src/vesc_driver.cpp index 06456a7..a390c9d 100644 --- a/vesc_driver/src/vesc_driver.cpp +++ b/vesc_driver/src/vesc_driver.cpp @@ -1,14 +1,224 @@ -#include +// -*- mode:c++; fill-column: 100; -*- -#include "vesc_driver.h" +#include "vesc_driver/vesc_driver.h" + +#include +#include + +#include +#include namespace vesc_driver { VescDriver::VescDriver(ros::NodeHandle nh, - ros::NodeHandle private_nh) + ros::NodeHandle private_nh) : + vesc_(std::string(), + boost::bind(&VescDriver::vescPacketCallback, this, _1), + boost::bind(&VescDriver::vescErrorCallback, this, _1)), + driver_mode_(MODE_INITIALIZING), fw_version_major_(-1), fw_version_minor_(-1) +{ + // get vesc serial port address + std::string port; + if (!private_nh.getParam("port", port)) { + ROS_FATAL("VESC communication port parameter required."); + ros::shutdown(); + return; + } + + // attempt to connect to the serial port + try { + vesc_.connect(port); + } + catch (SerialException e) { + ROS_FATAL("Failed to connect to the VESC, %s.", e.what()); + ros::shutdown(); + return; + } + + // create vesc state (telemetry) publisher + state_pub_ = private_nh.advertise("sensors/core", 10); + + // subscribe to motor and servo command topics + duty_cycle_sub_ = private_nh.subscribe("commands/motor/duty_cycle", + 10, &VescDriver::dutyCycleCallback, this); + current_sub_ = private_nh.subscribe("commands/motor/current", 10, + &VescDriver::currentCallback, this); + brake_sub_ = private_nh.subscribe("commands/motor/brake", 10, &VescDriver::brakeCallback, this); + speed_sub_ = private_nh.subscribe("commands/motor/speed", 10, &VescDriver::speedCallback, this); + position_sub_ = private_nh.subscribe("commands/motor/position", 10, + &VescDriver::positionCallback, this); + servo_sub_ = private_nh.subscribe("commands/servo/position", 10, + &VescDriver::servoCallback, this); + + // create a 50Hz timer, used for state machine & polling VESC telemetry + timer_ = nh.createTimer(ros::Duration(1.0/50.0), &VescDriver::timerCallback, this); +} + + /* TODO or TO-THINKABOUT LIST + - what should we do on startup? send brake or zero command? + - what to do if the vesc interface gives an error? + - check version number against know compatable? + - should we wait until we receive telemetry before sending commands? + - should we track the last motor command + - what to do if no motor command received recently? + - what to do if no servo command received recently? + - what is the motor safe off state (0 current?) + - what to do if a command parameter is out of range, ignore? + - try to predict vesc bounds (from vesc config) and command detect bounds errors + */ + +void VescDriver::timerCallback(const ros::TimerEvent& event) +{ + // VESC interface should not unexpectedly disconnect, but test for it anyway + if (!vesc_.isConnected()) { + ROS_FATAL("Unexpectedly disconnected from serial port."); + timer_.stop(); + ros::shutdown(); + return; + } + + /* + * Driver state machine, modes: + * INITIALIZING - request and wait for vesc version + * OPERATING - receiving commands from subscriber topics + */ + if (driver_mode_ == MODE_INITIALIZING) { + // request version number, return packet will update the internal version numbers + vesc_.requestFWVersion(); + if (fw_version_major_ >= 0 && fw_version_minor_ >= 0) { + ROS_INFO("Connected to VESC with firmware version %d.%d", + fw_version_major_, fw_version_minor_); + driver_mode_ = MODE_OPERATING; + } + } + else if (driver_mode_ == MODE_OPERATING) { + // poll for vesc state (telemetry) + vesc_.requestState(); + } + else { + // unknown mode, how did that happen? + assert(false && "unknown driver mode"); + } +} + +void VescDriver::vescPacketCallback(const boost::shared_ptr& packet) +{ + if (packet->name() == "Values") { + boost::shared_ptr values = + boost::dynamic_pointer_cast(packet); + + vesc_msgs::VescState state_msg; + state_msg.header.stamp = ros::Time::now(); + state_msg.voltage_input = values->v_in(); + state_msg.temperature_pcb = values->temp_pcb(); + state_msg.current_motor = values->current_motor(); + state_msg.current_input = values->current_in(); + state_msg.speed = values->rpm(); + state_msg.duty_cycle = values->duty_now(); + state_msg.charge_drawn = values->amp_hours(); + state_msg.charge_regen = values->amp_hours_charged(); + state_msg.energy_drawn = values->watt_hours(); + state_msg.energy_regen = values->watt_hours_charged(); + state_msg.displacement = values->tachometer(); + state_msg.distance_traveled = values->tachometer_abs(); + state_msg.fault_code = values->fault_code(); + + state_pub_.publish(state_msg); + } + else if (packet->name() == "FWVersion") { + boost::shared_ptr fw_version = + boost::dynamic_pointer_cast(packet); + // todo: might need lock here + fw_version_major_ = fw_version->fwMajor(); + fw_version_minor_ = fw_version->fwMinor(); + } +} + +void VescDriver::vescErrorCallback(const std::string& error) { - ROS_DEBUG("Constructing VescDriver"); + ROS_ERROR("%s", error.c_str()); +} + +/** + * @param duty_cycle Commanded VESC duty cycle. Valid range for this driver is -1 to +1. However, + * note that the VESC may impose a more restrictive bounds on the range depending + * on its configuration, e.g. absolute value is between 0.05 and 0.95. + */ +void VescDriver::dutyCycleCallback(const std_msgs::Float64::ConstPtr& duty_cycle) +{ + if (duty_cycle->data < -1.0 || duty_cycle->data > 1.0) { + ROS_ERROR("VESC duty cycle should be between -1 and 1, ignoring."); + return; + } + if (driver_mode_ = MODE_OPERATING) { + vesc_.setDutyCycle(duty_cycle->data); + } +} + +/** + * @param current Commanded VESC current in Amps. Any value is accepted by this driver. However, + * note that the VESC may impose a more restrictive bounds on the range depending on + * its configuration. + */ +void VescDriver::currentCallback(const std_msgs::Float64::ConstPtr& current) +{ + if (driver_mode_ = MODE_OPERATING) { + vesc_.setCurrent(current->data); + } +} + +/** + * @param brake Commanded VESC braking current in Amps. Any value is accepted by this driver. + * However, note that the VESC may impose a more restrictive bounds on the range + * depending on its configuration. + */ +void VescDriver::brakeCallback(const std_msgs::Float64::ConstPtr& brake) +{ + if (driver_mode_ = MODE_OPERATING) { + vesc_.setBrake(brake->data); + } +} + +/** + * @param speed Commanded VESC speed in electrical RPM. Electrical RPM is the mechanical RPM + * multiplied by the number of motor poles. Any value is accepted by this + * driver. However, note that the VESC may impose a more restrictive bounds on the + * range depending on its configuration. + */ +void VescDriver::speedCallback(const std_msgs::Float64::ConstPtr& speed) +{ + if (driver_mode_ = MODE_OPERATING) { + vesc_.setSpeed(speed->data); + } +} + +/** + * @param position Commanded VESC motor position in radians. Any value is accepted by this driver. + * Note that the VESC must be in encoder mode for this command to have an effect. + */ +void VescDriver::positionCallback(const std_msgs::Float64::ConstPtr& position) +{ + if (driver_mode_ = MODE_OPERATING) { + // ROS uses radians but VESC seems to use degrees. Convert to degrees. + double position_deg = position->data * M_PI / 180.0; + vesc_.setPosition(position_deg); + } +} + +/** + * @param servo Commanded VESC servo output position. Valid range is 0 to 1. + */ +void VescDriver::servoCallback(const std_msgs::Float64::ConstPtr& servo) +{ + if (servo->data < 0 || servo->data > 1.0) { + ROS_ERROR("VESC servo position should be between 0 and 1, ignoring."); + return; + } + + if (driver_mode_ = MODE_OPERATING) { + vesc_.setServo(servo->data); + } } } // namespace vesc_driver diff --git a/vesc_driver/src/vesc_driver.h b/vesc_driver/src/vesc_driver.h deleted file mode 100644 index 686224e..0000000 --- a/vesc_driver/src/vesc_driver.h +++ /dev/null @@ -1,22 +0,0 @@ -#ifndef VESC_DRIVER_VESC_DRIVER_H -#define VESC_DRIVER_VESC_DRIVER_H - -#include - -namespace vesc_driver -{ - -class VescDriver -{ -public: - - VescDriver(ros::NodeHandle nh, - ros::NodeHandle private_nh); - -private: - -}; - -} // namespace vesc_driver - -#endif // VESC_DRIVER_VESC_DRIVER_H diff --git a/vesc_driver/src/vesc_driver_node.cpp b/vesc_driver/src/vesc_driver_node.cpp index f06d865..115191e 100644 --- a/vesc_driver/src/vesc_driver_node.cpp +++ b/vesc_driver/src/vesc_driver_node.cpp @@ -1,6 +1,6 @@ #include -#include "vesc_driver.h" +#include "vesc_driver/vesc_driver.h" int main(int argc, char** argv) { diff --git a/vesc_driver/src/vesc_driver_nodelet.cpp b/vesc_driver/src/vesc_driver_nodelet.cpp index 8699a33..78c8d3b 100644 --- a/vesc_driver/src/vesc_driver_nodelet.cpp +++ b/vesc_driver/src/vesc_driver_nodelet.cpp @@ -1,10 +1,9 @@ -#include -#include -#include - #include +#include +#include +#include -#include "vesc_driver.h" +#include "vesc_driver/vesc_driver.h" namespace vesc_driver { diff --git a/vesc_driver/src/vesc_interface.cpp b/vesc_driver/src/vesc_interface.cpp new file mode 100644 index 0000000..84a2cf2 --- /dev/null +++ b/vesc_driver/src/vesc_interface.cpp @@ -0,0 +1,244 @@ +// -*- mode:c++; fill-column: 100; -*- + +#include "vesc_driver/vesc_interface.h" + +#include + +#include +#include +#include +#include + +#include +#include + +#include "vesc_driver/vesc_packet_factory.h" + +namespace vesc_driver +{ + +class VescInterface::Impl +{ +public: + Impl() : + serial_(std::string(), 115200, serial::Timeout::simpleTimeout(100), + serial::eightbits, serial::parity_none, serial::stopbits_one, serial::flowcontrol_none) + {} + + void* rxThread(void); + + static void* rxThreadHelper(void *context) + { + return ((VescInterface::Impl*)context)->rxThread(); + } + + pthread_t rx_thread_; + bool rx_thread_run_; + PacketHandlerFunction packet_handler_; + ErrorHandlerFunction error_handler_; + serial::Serial serial_; + VescFrame::CRC send_crc_; +}; + +void* VescInterface::Impl::rxThread(void) +{ + Buffer buffer; + buffer.reserve(4096); + + while (rx_thread_run_) { + + int bytes_needed = VescFrame::VESC_MIN_FRAME_SIZE; + if (!buffer.empty()) { + + // search buffer for valid packet(s) + Buffer::iterator iter(buffer.begin()); + Buffer::iterator iter_begin(buffer.begin()); + while (iter != buffer.end()) { + + // check if valid start-of-frame character + if (VescFrame::VESC_SOF_VAL_SMALL_FRAME == *iter || + VescFrame::VESC_SOF_VAL_LARGE_FRAME == *iter) { + + // good start, now attempt to create packet + std::string error; + VescPacketConstPtr packet = + VescPacketFactory::createPacket(iter, buffer.end(), &bytes_needed, &error); + if (packet) { + // good packet, check if we skipped any data + if (std::distance(iter_begin, iter) > 0) { + std::ostringstream ss; + ss << "Out-of-sync with VESC, unknown data leading valid frame. Discarding " + << std::distance(iter_begin, iter) << " bytes."; + error_handler_(ss.str()); + } + // call packet handler + packet_handler_(packet); + // update state + iter = iter + packet->frame().size(); + iter_begin = iter; + // continue to look for another frame in buffer + continue; + } + else if (bytes_needed > 0) { + // need more data, break out of while loop + break; // for (iter_sof... + } + else { + // else, this was not a packet, move on to next byte + error_handler_(error); + } + } + + iter++; + } + + // if iter is at the end of the buffer, more bytes are needed + if (iter == buffer.end()) + bytes_needed = VescFrame::VESC_MIN_FRAME_SIZE; + + // erase "used" buffer + if (std::distance(iter_begin, iter) > 0) { + std::ostringstream ss; + ss << "Out-of-sync with VESC, discarding " << std::distance(iter_begin, iter) << " bytes."; + error_handler_(ss.str()); + } + buffer.erase(buffer.begin(), iter); + } + + // attempt to read at least bytes_needed bytes from the serial port + int bytes_to_read = + std::max(bytes_needed, std::min(4096, static_cast(serial_.available()))); + int bytes_read = serial_.read(buffer, bytes_to_read); + if (bytes_needed > 0 && 0 == bytes_read && !buffer.empty()) { + error_handler_("Possibly out-of-sync with VESC, read timout in the middle of a frame."); + } + + } +} + + +VescInterface::VescInterface(const std::string& port, + const PacketHandlerFunction& packet_handler, + const ErrorHandlerFunction& error_handler) : + impl_(new Impl()) +{ + setPacketHandler(packet_handler); + setErrorHandler(error_handler); + // attempt to conect if the port is specified + if (!port.empty()) + connect(port); +} + +VescInterface::~VescInterface() +{ + disconnect(); +} + +void VescInterface::setPacketHandler(const PacketHandlerFunction& handler) +{ + // todo - definately need mutex + impl_->packet_handler_ = handler; +} + +void VescInterface::setErrorHandler(const ErrorHandlerFunction& handler) +{ + // todo - definately need mutex + impl_->error_handler_ = handler; +} + +void VescInterface::connect(const std::string& port) +{ + // todo - mutex? + + if (isConnected()) { + throw SerialException("Already connected to serial port."); + } + + // connect to serial port + try { + impl_->serial_.setPort(port); + impl_->serial_.open(); + } + catch (const std::exception& e) { + std::stringstream ss; + ss << "Failed to open the serial port to the VESC. " << e.what(); + throw SerialException(ss.str().c_str()); + } + + // start up a monitoring thread + impl_->rx_thread_run_ = true; + int result = + pthread_create(&impl_->rx_thread_, NULL, &VescInterface::Impl::rxThreadHelper, impl_.get()); + assert(0 == result); +} + +void VescInterface::disconnect() +{ + // todo - mutex? + + if (isConnected()) { + // bring down read thread + impl_->rx_thread_run_ = false; + int result = pthread_join(impl_->rx_thread_, NULL); + assert(0 == result); + + impl_->serial_.close(); + } +} + +bool VescInterface::isConnected() const +{ + return impl_->serial_.isOpen(); +} + +void VescInterface::send(const VescPacket& packet) +{ + size_t written = impl_->serial_.write(packet.frame()); + if (written != packet.frame().size()) { + std::stringstream ss; + ss << "Wrote " << written << " bytes, expected " << packet.frame().size() << "."; + throw SerialException(ss.str().c_str()); + } +} + +void VescInterface::requestFWVersion() +{ + send(VescPacketRequestFWVersion()); +} + +void VescInterface::requestState() +{ + send(VescPacketRequestValues()); +} + +void VescInterface::setDutyCycle(double duty_cycle) +{ + send(VescPacketSetDuty(duty_cycle)); +} + +void VescInterface::setCurrent(double current) +{ + send(VescPacketSetCurrent(current)); +} + +void VescInterface::setBrake(double brake) +{ + send(VescPacketSetCurrentBrake(brake)); +} + +void VescInterface::setSpeed(double speed) +{ + send(VescPacketSetRPM(speed)); +} + +void VescInterface::setPosition(double position) +{ + send(VescPacketSetPos(position)); +} + +void VescInterface::setServo(double servo) +{ + send(VescPacketSetServoPos(servo)); +} + +} // namespace vesc_driver diff --git a/vesc_driver/src/vesc_packet.cpp b/vesc_driver/src/vesc_packet.cpp new file mode 100644 index 0000000..80328a7 --- /dev/null +++ b/vesc_driver/src/vesc_packet.cpp @@ -0,0 +1,368 @@ +// -*- mode:c++; fill-column: 100; -*- + +#include "vesc_driver/vesc_packet.h" + +#include +#include + +#include +#include +#include + +#include "vesc_driver/vesc_packet_factory.h" +#include "vesc_driver/datatypes.h" + +namespace vesc_driver +{ + +VescFrame::VescFrame(int payload_size) +{ + assert(payload_size >= 0 && payload_size <= 1024); + + if (payload_size < 256) { + // single byte payload size + frame_.reset(new Buffer(VESC_MIN_FRAME_SIZE + payload_size)); + *frame_->begin() = 2; + *(frame_->begin() + 1) = payload_size; + payload_.first = frame_->begin() + 2; + } + else { + // two byte payload size + frame_.reset(new Buffer(VESC_MIN_FRAME_SIZE + 1 + payload_size)); + *frame_->begin() = 3; + *(frame_->begin() + 1) = payload_size >> 8; + *(frame_->begin() + 2) = payload_size & 0xFF; + payload_.first = frame_->begin() + 3; + } + + payload_.second = payload_.first + payload_size; + *(frame_->end() - 1) = 3; +} + +VescFrame::VescFrame(const BufferRangeConst& frame, const BufferRangeConst& payload) +{ + /* VescPacketFactory::createPacket() should make sure that the input is valid, but run a few cheap + checks anyway */ + assert(boost::distance(frame) >= VESC_MIN_FRAME_SIZE); + assert(boost::distance(frame) <= VESC_MAX_FRAME_SIZE); + assert(boost::distance(payload) <= VESC_MAX_PAYLOAD_SIZE); + assert(std::distance(frame.first, payload.first) > 0 && + std::distance(payload.second, frame.second) > 0); + + frame_.reset(new Buffer(boost::begin(frame), boost::end(frame))); + payload_.first = frame_->begin() + std::distance(frame.first, payload.first); + payload_.second = frame_->begin() + std::distance(frame.first, payload.second); +} + +VescPacket::VescPacket(const std::string& name, int payload_size, int payload_id) : + VescFrame(payload_size), name_(name) +{ + assert(payload_id >= 0 && payload_id < 256); + assert(boost::distance(payload_) > 0); + *payload_.first = payload_id; +} + +VescPacket::VescPacket(const std::string& name, boost::shared_ptr raw) : + VescFrame(*raw), name_(name) +{ +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketFWVersion::VescPacketFWVersion(boost::shared_ptr raw) : + VescPacket("FWVersion", raw) +{ +} + +int VescPacketFWVersion::fwMajor() const +{ + return *(payload_.first + 1); +} + +int VescPacketFWVersion::fwMinor() const +{ + return *(payload_.first + 2); +} + +REGISTER_PACKET_TYPE(COMM_FW_VERSION, VescPacketFWVersion) + +VescPacketRequestFWVersion::VescPacketRequestFWVersion() : + VescPacket("RequestFWVersion", 1, COMM_FW_VERSION) +{ + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketValues::VescPacketValues(boost::shared_ptr raw) : + VescPacket("Values", raw) +{ +} + +double VescPacketValues::temp_mos1() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 1)) << 8) + + static_cast(*(payload_.first + 2))); + return static_cast(v) / 10.0; +} +double VescPacketValues::temp_mos2() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 3)) << 8) + + static_cast(*(payload_.first + 4))); + return static_cast(v) / 10.0; +} +double VescPacketValues::temp_mos3() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 5)) << 8) + + static_cast(*(payload_.first + 6))); + return static_cast(v) / 10.0; +} +double VescPacketValues::temp_mos4() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 7)) << 8) + + static_cast(*(payload_.first + 8))); + return static_cast(v) / 10.0; +} +double VescPacketValues::temp_mos5() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 9)) << 8) + + static_cast(*(payload_.first + 10))); + return static_cast(v) / 10.0; +} +double VescPacketValues::temp_mos6() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 11)) << 8) + + static_cast(*(payload_.first + 12))); + return static_cast(v) / 10.0; +} +double VescPacketValues::temp_pcb() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 13)) << 8) + + static_cast(*(payload_.first + 14))); + return static_cast(v) / 10.0; +} +double VescPacketValues::current_motor() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 15)) << 24) + + (static_cast(*(payload_.first + 16)) << 16) + + (static_cast(*(payload_.first + 17)) << 8) + + static_cast(*(payload_.first + 18))); + return static_cast(v) / 100.0; +} +double VescPacketValues::current_in() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 19)) << 24) + + (static_cast(*(payload_.first + 20)) << 16) + + (static_cast(*(payload_.first + 21)) << 8) + + static_cast(*(payload_.first + 22))); + return static_cast(v) / 100.0; +} +double VescPacketValues::duty_now() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 23)) << 8) + + static_cast(*(payload_.first + 24))); + return static_cast(v) / 1000.0; +} +double VescPacketValues::rpm() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 25)) << 24) + + (static_cast(*(payload_.first + 26)) << 16) + + (static_cast(*(payload_.first + 27)) << 8) + + static_cast(*(payload_.first + 28))); + return static_cast(v); +} +double VescPacketValues::v_in() const +{ + int16_t v = static_cast((static_cast(*(payload_.first + 29)) << 8) + + static_cast(*(payload_.first + 30))); + return static_cast(v) / 10.0; +} +double VescPacketValues::amp_hours() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 31)) << 24) + + (static_cast(*(payload_.first + 32)) << 16) + + (static_cast(*(payload_.first + 33)) << 8) + + static_cast(*(payload_.first + 34))); + return static_cast(v); +} +double VescPacketValues::amp_hours_charged() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 35)) << 24) + + (static_cast(*(payload_.first + 36)) << 16) + + (static_cast(*(payload_.first + 37)) << 8) + + static_cast(*(payload_.first + 38))); + return static_cast(v); +} +double VescPacketValues::watt_hours() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 39)) << 24) + + (static_cast(*(payload_.first + 40)) << 16) + + (static_cast(*(payload_.first + 41)) << 8) + + static_cast(*(payload_.first + 42))); + return static_cast(v); +} +double VescPacketValues::watt_hours_charged() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 43)) << 24) + + (static_cast(*(payload_.first + 44)) << 16) + + (static_cast(*(payload_.first + 45)) << 8) + + static_cast(*(payload_.first + 46))); + return static_cast(v); +} +double VescPacketValues::tachometer() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 47)) << 24) + + (static_cast(*(payload_.first + 48)) << 16) + + (static_cast(*(payload_.first + 49)) << 8) + + static_cast(*(payload_.first + 50))); + return static_cast(v); +} +double VescPacketValues::tachometer_abs() const +{ + int32_t v = static_cast((static_cast(*(payload_.first + 51)) << 24) + + (static_cast(*(payload_.first + 52)) << 16) + + (static_cast(*(payload_.first + 53)) << 8) + + static_cast(*(payload_.first + 54))); + return static_cast(v); +} +int VescPacketValues::fault_code() const +{ + return static_cast(*(payload_.first + 55)); +} + +REGISTER_PACKET_TYPE(COMM_GET_VALUES, VescPacketValues) + +VescPacketRequestValues::VescPacketRequestValues() : + VescPacket("RequestFWVersion", 1, COMM_GET_VALUES) +{ + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + + +VescPacketSetDuty::VescPacketSetDuty(double duty) : + VescPacket("SetDuty", 5, COMM_SET_DUTY) +{ + /** @todo range check duty */ + + int32_t v = static_cast(duty * 100000.0); + + *(payload_.first + 1) = static_cast((static_cast(v) >> 24) & 0xFF); + *(payload_.first + 2) = static_cast((static_cast(v) >> 16) & 0xFF); + *(payload_.first + 3) = static_cast((static_cast(v) >> 8) & 0xFF); + *(payload_.first + 4) = static_cast(static_cast(v) & 0xFF); + + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketSetCurrent::VescPacketSetCurrent(double current) : + VescPacket("SetCurrent", 5, COMM_SET_CURRENT) +{ + int32_t v = static_cast(current * 1000.0); + + *(payload_.first + 1) = static_cast((static_cast(v) >> 24) & 0xFF); + *(payload_.first + 2) = static_cast((static_cast(v) >> 16) & 0xFF); + *(payload_.first + 3) = static_cast((static_cast(v) >> 8) & 0xFF); + *(payload_.first + 4) = static_cast(static_cast(v) & 0xFF); + + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketSetCurrentBrake::VescPacketSetCurrentBrake(double current_brake) : + VescPacket("SetCurrentBrake", 5, COMM_SET_CURRENT_BRAKE) +{ + int32_t v = static_cast(current_brake * 1000.0); + + *(payload_.first + 1) = static_cast((static_cast(v) >> 24) & 0xFF); + *(payload_.first + 2) = static_cast((static_cast(v) >> 16) & 0xFF); + *(payload_.first + 3) = static_cast((static_cast(v) >> 8) & 0xFF); + *(payload_.first + 4) = static_cast(static_cast(v) & 0xFF); + + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketSetRPM::VescPacketSetRPM(double rpm) : + VescPacket("SetRPM", 5, COMM_SET_RPM) +{ + int32_t v = static_cast(rpm); + + *(payload_.first + 1) = static_cast((static_cast(v) >> 24) & 0xFF); + *(payload_.first + 2) = static_cast((static_cast(v) >> 16) & 0xFF); + *(payload_.first + 3) = static_cast((static_cast(v) >> 8) & 0xFF); + *(payload_.first + 4) = static_cast(static_cast(v) & 0xFF); + + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketSetPos::VescPacketSetPos(double pos) : + VescPacket("SetPos", 5, COMM_SET_POS) +{ + /** @todo range check pos */ + + int32_t v = static_cast(pos * 1000000.0); + + *(payload_.first + 1) = static_cast((static_cast(v) >> 24) & 0xFF); + *(payload_.first + 2) = static_cast((static_cast(v) >> 16) & 0xFF); + *(payload_.first + 3) = static_cast((static_cast(v) >> 8) & 0xFF); + *(payload_.first + 4) = static_cast(static_cast(v) & 0xFF); + + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +/*------------------------------------------------------------------------------------------------*/ + +VescPacketSetServoPos::VescPacketSetServoPos(double servo_pos) : + VescPacket("SetServoPos", 3, COMM_SET_SERVO_POS) +{ + /** @todo range check pos */ + + int16_t v = static_cast(servo_pos * 1000.0); + + *(payload_.first + 1) = static_cast((static_cast(v) >> 8) & 0xFF); + *(payload_.first + 2) = static_cast(static_cast(v) & 0xFF); + + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*payload_.first), boost::distance(payload_)); + uint16_t crc = crc_calc.checksum(); + *(frame_->end() - 3) = static_cast(crc >> 8); + *(frame_->end() - 2) = static_cast(crc & 0xFF); +} + +} // namespace vesc_driver diff --git a/vesc_driver/src/vesc_packet_factory.cpp b/vesc_driver/src/vesc_packet_factory.cpp new file mode 100644 index 0000000..470f9c5 --- /dev/null +++ b/vesc_driver/src/vesc_packet_factory.cpp @@ -0,0 +1,124 @@ +// -*- mode:c++; fill-column: 100; -*- + +#include "vesc_driver/vesc_packet_factory.h" + +#include +#include + +#include +#include +#include + +#include "vesc_driver/vesc_packet.h" + +namespace vesc_driver +{ + +/** Construct map on first use */ +VescPacketFactory::FactoryMap* VescPacketFactory::getMap() +{ + static FactoryMap m; + return &m; +} + +void VescPacketFactory::registerPacketType(int payload_id, CreateFn fn) +{ + FactoryMap* p_map(getMap()); + assert(0 == p_map->count(payload_id)); + (*p_map)[payload_id] = fn; +} + +/** Helper function for when createPacket can not create a packet */ +VescPacketPtr createFailed(int* p_num_bytes_needed, std::string* p_what, + const std::string& what, int num_bytes_needed = 0) +{ + if (p_num_bytes_needed != NULL) *p_num_bytes_needed = num_bytes_needed; + if (p_what != NULL) *p_what = what; + return VescPacketPtr(); +} + +VescPacketPtr VescPacketFactory::createPacket(const Buffer::const_iterator& begin, + const Buffer::const_iterator& end, + int* num_bytes_needed, std::string* what) +{ + // initialize output variables + if (num_bytes_needed != NULL) *num_bytes_needed = 0; + if (what != NULL) what->clear(); + + // need at least VESC_MIN_FRAME_SIZE bytes in buffer + int buffer_size(std::distance(begin, end)); + if (buffer_size < VescFrame::VESC_MIN_FRAME_SIZE) + return createFailed(num_bytes_needed, what, "Buffer does not contain a complete frame", + VescFrame::VESC_MIN_FRAME_SIZE - buffer_size); + + // buffer must begin with a start-of-frame + if (VescFrame::VESC_SOF_VAL_SMALL_FRAME != *begin && + VescFrame::VESC_SOF_VAL_LARGE_FRAME != *begin) + return createFailed(num_bytes_needed, what, "Buffer must begin with start-of-frame character"); + + // get a view of the payload + BufferRangeConst view_payload; + if (VescFrame::VESC_SOF_VAL_SMALL_FRAME == *begin) { + // payload size field is one byte + view_payload.first = begin + 2; + view_payload.second = view_payload.first + *(begin + 1); + } + else { + assert(VescFrame::VESC_SOF_VAL_LARGE_FRAME == *begin); + // payload size field is two bytes + view_payload.first = begin + 3; + view_payload.second = view_payload.first + (*(begin + 1) << 8) + *(begin + 2); + } + + // check length + if (boost::distance(view_payload) > VescFrame::VESC_MAX_PAYLOAD_SIZE) + return createFailed(num_bytes_needed, what, "Invalid payload length"); + + // get iterators to crc field, end-of-frame field, and a view of the whole frame + Buffer::const_iterator iter_crc(view_payload.second); + Buffer::const_iterator iter_eof(iter_crc + 2); + BufferRangeConst view_frame(begin, iter_eof + 1); + + // do we have enough data in the buffer to complete the frame? + int frame_size = boost::distance(view_frame); + if (buffer_size < frame_size) + return createFailed(num_bytes_needed, what, "Buffer does not contain a complete frame", + frame_size - buffer_size); + + // is the end-of-frame character valid? + if (VescFrame::VESC_EOF_VAL != *iter_eof) + return createFailed(num_bytes_needed, what, "Invalid end-of-frame character"); + + // is the crc valid? + unsigned short crc = (static_cast(*iter_crc) << 8) + *(iter_crc + 1); + VescFrame::CRC crc_calc; + crc_calc.process_bytes(&(*view_payload.first), boost::distance(view_payload)); + if (crc != crc_calc.checksum()) + return createFailed(num_bytes_needed, what, "Invalid checksum"); + + // frame looks good, construct the raw frame + boost::shared_ptr raw_frame(new VescFrame(view_frame, view_payload)); + + // if the packet has a payload, construct the corresponding subclass + if (boost::distance(view_payload) > 0) { + + // get constructor function from payload id + FactoryMap* p_map(getMap()); + FactoryMap::const_iterator search(p_map->find(*view_payload.first)); + if (search != p_map->end()) { + return search->second(raw_frame); + } + else { + // no subclass constructor for this packet + return createFailed(num_bytes_needed, what, "Unkown payload type."); + } + + } + else { + // no payload + return createFailed(num_bytes_needed, what, "Frame does not have a payload"); + } +} + + +} // namesapce vesc_driver diff --git a/vesc_msgs/CMakeLists.txt b/vesc_msgs/CMakeLists.txt index 2e9ea90..29699a0 100644 --- a/vesc_msgs/CMakeLists.txt +++ b/vesc_msgs/CMakeLists.txt @@ -9,7 +9,7 @@ find_package(catkin REQUIRED COMPONENTS add_message_files( DIRECTORY msg FILES - VescTelemetry.msg + VescState.msg ) generate_messages( DEPENDENCIES diff --git a/vesc_msgs/msg/VescState.msg b/vesc_msgs/msg/VescState.msg new file mode 100644 index 0000000..055b49c --- /dev/null +++ b/vesc_msgs/msg/VescState.msg @@ -0,0 +1,25 @@ +# Vedder VESC open source motor controller state (telemetry) + +# fault codes +int32 FAULT_CODE_NONE=0 +int32 FAULT_CODE_OVER_VOLTAGE=1 +int32 FAULT_CODE_UNDER_VOLTAGE=2 +int32 FAULT_CODE_DRV8302=3 +int32 FAULT_CODE_ABS_OVER_CURRENT=4 +int32 FAULT_CODE_OVER_TEMP_FET=5 +int32 FAULT_CODE_OVER_TEMP_MOTOR=6 + +Header header +float64 voltage_input # input voltage (volt) +float64 temperature_pcb # temperature of printed circuit board (degrees Celsius) +float64 current_motor # motor current (ampere) +float64 current_input # input current (ampere) +float64 speed # motor electrical speed (revolutions per minute) +float64 duty_cycle # duty cycle (0 to 1) +float64 charge_drawn # electric charge drawn from input (ampere-hour) +float64 charge_regen # electric charge regenerated to input (ampere-hour) +float64 energy_drawn # energy drawn from input (watt-hour) +float64 energy_regen # energy regenerated to input (watt-hour) +float64 displacement # net tachometer (counts) +float64 distance_traveled # total tachnometer (counts) +int32 fault_code diff --git a/vesc_msgs/msg/VescTelemetry.msg b/vesc_msgs/msg/VescTelemetry.msg deleted file mode 100644 index 54bd073..0000000 --- a/vesc_msgs/msg/VescTelemetry.msg +++ /dev/null @@ -1,25 +0,0 @@ -# Vedder VESC open source motor controller telemetry - -# fault codes -int32 FAULT_CODE_NONE=0 -int32 FAULT_CODE_OVER_VOLTAGE=1 -int32 FAULT_CODE_UNDER_VOLTAGE=2 -int32 FAULT_CODE_DRV8302=3 -int32 FAULT_CODE_ABS_OVER_CURRENT=4 -int32 FAULT_CODE_OVER_TEMP_FET=5 -int32 FAULT_CODE_OVER_TEMP_MOTOR=6 - -Header header -float32 voltage_input # input voltage (volt) -float32 temperature_pcb # temperature of printed circuit board (degrees Celsius) -float32 current_motor # motor current (ampere) -float32 current_input # input current (ampere) -float32 speed # motor electrical speed (revolutions per minute) -float32 duty_cycle # duty cycle (0 to 1) -float32 charge_drawn # electric charge drawn from input (ampere-hour) -float32 charge_regen # electric charge regenerated to input (ampere-hour) -float32 energy_drawn # energy drawn from input (watt-hour) -float32 energy_regen # energy regenerated to input (watt-hour) -int32 displacement # net tachometer (counts) -int32 distance_traveled # total tachnometer (counts) -int32 fault_code