sr_ronex_simple_controller.cpp
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 
00024 #include "sr_ronex_examples/sr_ronex_simple_controller.hpp"
00025 #include "pluginlib/class_list_macros.h"
00026 
00027 PLUGINLIB_EXPORT_CLASS( ronex::SrRoNeXSimpleController, controller_interface::ControllerBase)
00028 
00029 namespace ronex
00030 {
00031 SrRoNeXSimpleController::SrRoNeXSimpleController()
00032   : loop_count_(0)
00033 {
00034 }
00035 
00036 SrRoNeXSimpleController::~SrRoNeXSimpleController()
00037 {
00038 }
00039 
00040 bool SrRoNeXSimpleController::init(ros_ethercat_model::RobotState* robot, ros::NodeHandle &n)
00041 {
00042   assert (robot);
00043   
00044   std::string path("/ronex/general_io/test_ronex");
00045   general_io_ = static_cast<ronex::GeneralIO*>( robot->getCustomHW(path) );
00046   if( general_io_ == NULL)
00047   {
00048     ROS_ERROR_STREAM("Could not find RoNeX module (i.e., test_ronex). The controller is not loaded.");
00049     return false;
00050   }
00051   
00052   return true;
00053 }
00054 
00055 void SrRoNeXSimpleController::starting(const ros::Time&)
00056 {
00057   // Do nothing.
00058 }
00059 
00060 void SrRoNeXSimpleController::update(const ros::Time&, const ros::Duration&)
00061 {
00062   double position = general_io_->state_.analogue_[0];
00063   if (loop_count_++ % 100 == 0)
00064   {
00065     ROS_INFO_STREAM( "Position = " << position );
00066     loop_count_ = 0;
00067   }
00068 }
00069 
00070 void SrRoNeXSimpleController::stopping(const ros::Time&)
00071 {
00072   // Do nothing.
00073 } 
00074 
00075 }
00076 


sr_ronex_examples
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless, Yi Li
autogenerated on Fri Aug 28 2015 13:12:34