serial_proxy.h
Go to the documentation of this file.
00001 /*
00002     Copyright (c) 2011, Antons Rebguns <email>
00003     All rights reserved.
00004 
00005     Redistribution and use in source and binary forms, with or without
00006     modification, are permitted provided that the following conditions are met:
00007         * Redistributions of source code must retain the above copyright
00008         notice, this list of conditions and the following disclaimer.
00009         * Redistributions in binary form must reproduce the above copyright
00010         notice, this list of conditions and the following disclaimer in the
00011         documentation and/or other materials provided with the distribution.
00012         * Neither the name of the <organization> nor the
00013         names of its contributors may be used to endorse or promote products
00014         derived from this software without specific prior written permission.
00015 
00016     THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
00017     EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018     WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019     DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
00020     DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021     (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022     LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023     ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024     (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025     SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef SERIAL_PROXY_H__
00029 #define SERIAL_PROXY_H__
00030 
00031 #include <stdint.h>
00032 #include <string>
00033 #include <vector>
00034 #include <map>
00035 
00036 #include <boost/thread.hpp>
00037 
00038 #include <dynamixel_hardware_interface/dynamixel_io.h>
00039 #include <dynamixel_hardware_interface/MotorStateList.h>
00040 
00041 #include <ros/ros.h>
00042 #include <diagnostic_updater/update_functions.h>
00043 
00044 namespace dynamixel_hardware_interface
00045 {
00046 
00047 class SerialProxy
00048 {
00049 public:
00050     SerialProxy(std::string port_name,
00051                 std::string port_namespace,
00052                 std::string baud_rate,
00053                 int min_motor_id=1,
00054                 int max_motor_id=25,
00055                 double update_rate=10,
00056                 double diagnostics_rate=1,
00057                 int error_level_temp=65,
00058                 int warn_level_temp=60);
00059 
00060     ~SerialProxy();
00061 
00062     bool connect();
00063     void disconnect();
00064     
00065     DynamixelIO* getSerialPort();
00066 
00067 private:
00068     ros::NodeHandle nh_;
00069 
00070     std::string port_name_;
00071     std::string port_namespace_;
00072     std::string baud_rate_;
00073     int min_motor_id_;
00074     int max_motor_id_;
00075     double update_rate_;
00076     double diagnostics_rate_;
00077     int error_level_temp_;
00078     int warn_level_temp_;
00079 
00080     MotorStateListPtr current_state_;
00081 
00082     ros::Publisher motor_states_pub_;
00083     ros::Publisher diagnostics_pub_;
00084 
00085     boost::thread* feedback_thread_;
00086     boost::thread* diagnostics_thread_;
00087 
00088     boost::mutex terminate_mutex_;
00089     bool terminate_feedback_;
00090     bool terminate_diagnostics_;
00091 
00092     DynamixelIO* dxl_io_;
00093     std::vector<int> motors_;
00094     std::map<int, const DynamixelData*> motor_static_info_;
00095 
00096     void fillMotorParameters(const DynamixelData* motor_data);
00097     bool findMotors();
00098     void updateMotorStates();
00099     void publishDiagnosticInformation();
00100     
00101     diagnostic_updater::FrequencyStatus freq_status_;
00102 };
00103 
00104 }
00105 
00106 #endif // SERIAL_PROXY_H__


dynamixel_hardware_interface
Author(s): Antons Rebguns
autogenerated on Fri Aug 28 2015 10:32:45