fake_calibration_controller.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Shadow Robot Company, All rights reserved.
00003  *
00004  * This library is free software; you can redistribute it and/or
00005  * modify it under the terms of the GNU Lesser General Public
00006  * License as published by the Free Software Foundation; either
00007  * version 3.0 of the License, or (at your option) any later version.
00008  *
00009  * This library is distributed in the hope that it will be useful,
00010  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00011  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
00012  * Lesser General Public License for more details.
00013  *
00014  * You should have received a copy of the GNU Lesser General Public
00015  * License along with this library.
00016  */
00017 
00025 #ifndef _FAKE_CALIBRATION_CONTROLLER_H_
00026 #define _FAKE_CALIBRATION_CONTROLLER_H_
00027 
00028 #include <ros/node_handle.h>
00029 
00030 #include <boost/smart_ptr.hpp>
00031 #include "ros_ethercat_model/robot_state.hpp"
00032 #include "realtime_tools/realtime_publisher.h"
00033 #include "std_msgs/Bool.h"
00034 #include <controller_interface/controller.h>
00035 #include <sr_ronex_hardware_interface/mk2_gio_hardware_interface.hpp>
00036 
00037 namespace ronex
00038 {
00039   class FakeCalibrationController
00040     : public controller_interface::Controller<ros_ethercat_model::RobotState>
00041   {
00042   public:
00043     FakeCalibrationController();
00044 
00045     virtual bool init(ros_ethercat_model::RobotState* robot, ros::NodeHandle &n);
00046 
00050     virtual void update(const ros::Time&, const ros::Duration&);
00051 
00052   private:
00053     ros_ethercat_model::RobotState* robot_;
00054     ros::NodeHandle node_;
00055     boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Bool> > pub_calibrated_;
00056     ros::Time last_publish_time_;
00057 
00058     enum { INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED };
00059     int state_;
00060 
00061     ros_ethercat_model::JointState *joint_;
00062     std::string joint_name_;
00063 
00064     std_msgs::Bool calib_msg_;
00065   };
00066 }
00067 
00068 /* For the emacs weenies in the crowd.
00069 Local Variables:
00070    c-basic-offset: 2
00071 End:
00072 */
00073 
00074 #endif /* _FAKE_CALIBRATION_CONTROLLER_H_ */


sr_ronex_controllers
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Fri Aug 28 2015 13:12:37