joint_feedback.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2013, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *      * Redistributions of source code must retain the above copyright
00011  *      notice, this list of conditions and the following disclaimer.
00012  *      * Redistributions in binary form must reproduce the above copyright
00013  *      notice, this list of conditions and the following disclaimer in the
00014  *      documentation and/or other materials provided with the distribution.
00015  *      * Neither the name of the Southwest Research Institute, nor the names
00016  *      of its contributors may be used to endorse or promote products derived
00017  *      from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #ifndef JOINT_FEEDBACK_H
00033 #define JOINT_FEEDBACK_H
00034 
00035 #ifndef FLATHEADERS
00036 #include "simple_message/joint_data.h"
00037 #include "simple_message/simple_message.h"
00038 #include "simple_message/simple_serialize.h"
00039 #include "simple_message/shared_types.h"
00040 #else
00041 #include "joint_data.h"
00042 #include "simple_message.h"
00043 #include "simple_serialize.h"
00044 #include "shared_types.h"
00045 #endif
00046 
00047 namespace industrial
00048 {
00049 namespace joint_feedback
00050 {
00051 
00052 namespace ValidFieldTypes
00053 {
00054 enum ValidFieldType
00055 {
00056   TIME = 0x01, POSITION = 0x02, VELOCITY = 0x04, ACCELERATION = 0x08
00057 };
00058 }
00059 typedef ValidFieldTypes::ValidFieldType ValidFieldType;
00060 
00083 class JointFeedback : public industrial::simple_serialize::SimpleSerialize
00084 {
00085 public:
00086 
00093   JointFeedback(void);
00098   ~JointFeedback(void);
00099 
00104   void init();
00105 
00110   void init(industrial::shared_types::shared_int robot_id,
00111             industrial::shared_types::shared_int valid_fields,
00112             industrial::shared_types::shared_real time,
00113             industrial::joint_data::JointData & positions,
00114             industrial::joint_data::JointData & velocities,
00115             industrial::joint_data::JointData & accelerations);
00116 
00123   void setRobotID(industrial::shared_types::shared_int robot_id)
00124   {
00125     this->robot_id_ = robot_id;
00126   }
00127 
00134   industrial::shared_types::shared_int getRobotID()
00135   {
00136     return this->robot_id_;
00137   }
00138 
00144   void setTime(industrial::shared_types::shared_real time)
00145   {
00146     this->time_ = time;
00147     this->valid_fields_ |= ValidFieldTypes::TIME;  // set the bit
00148   }
00149 
00156   bool getTime(industrial::shared_types::shared_real & time)
00157   {
00158     time = this->time_;
00159     return is_valid(ValidFieldTypes::TIME);
00160   }
00161 
00165   void clearTime()
00166   {
00167     this->time_ = 0;
00168     this->valid_fields_ &= ~ValidFieldTypes::TIME;  // clear the bit
00169   }
00170 
00176   void setPositions(industrial::joint_data::JointData &positions)
00177   {
00178     this->positions_.copyFrom(positions);
00179     this->valid_fields_ |= ValidFieldTypes::POSITION;  // set the bit
00180   }
00181 
00188   bool getPositions(industrial::joint_data::JointData &dest)
00189   {
00190     dest.copyFrom(this->positions_);
00191     return is_valid(ValidFieldTypes::POSITION);
00192   }
00193 
00197   void clearPositions()
00198   {
00199     this->positions_.init();
00200     this->valid_fields_ &= ~ValidFieldTypes::POSITION;  // clear the bit
00201   }
00202 
00208   void setVelocities(industrial::joint_data::JointData &velocities)
00209   {
00210     this->velocities_.copyFrom(velocities);
00211     this->valid_fields_ |= ValidFieldTypes::VELOCITY;  // set the bit
00212   }
00213 
00220   bool getVelocities(industrial::joint_data::JointData &dest)
00221   {
00222     dest.copyFrom(this->velocities_);
00223     return is_valid(ValidFieldTypes::VELOCITY);
00224   }
00225 
00229   void clearVelocities()
00230   {
00231     this->velocities_.init();
00232     this->valid_fields_ &= ~ValidFieldTypes::VELOCITY;  // clear the bit
00233   }
00239   void setAccelerations(industrial::joint_data::JointData &accelerations)
00240   {
00241     this->accelerations_.copyFrom(accelerations);
00242     this->valid_fields_ |= ValidFieldTypes::ACCELERATION;  // set the bit
00243   }
00244 
00251   bool getAccelerations(industrial::joint_data::JointData &dest)
00252   {
00253     dest.copyFrom(this->accelerations_);
00254     return is_valid(ValidFieldTypes::ACCELERATION);
00255   }
00256 
00260   void clearAccelerations()
00261   {
00262     this->accelerations_.init();
00263     this->valid_fields_ &= ~ValidFieldTypes::ACCELERATION;  // clear the bit
00264   }
00265 
00266 
00272   void copyFrom(JointFeedback &src);
00273 
00279   bool operator==(JointFeedback &rhs);
00280 
00286   bool is_valid(ValidFieldType field)
00287   {
00288     return valid_fields_ & field;
00289   }
00290 
00291   // Overrides - SimpleSerialize
00292   bool load(industrial::byte_array::ByteArray *buffer);
00293   bool unload(industrial::byte_array::ByteArray *buffer);
00294   unsigned int byteLength()
00295   {
00296     return 2*sizeof(industrial::shared_types::shared_int) + sizeof(industrial::shared_types::shared_real)
00297         + 3*this->positions_.byteLength();
00298   }
00299 
00300 private:
00301 
00305   industrial::shared_types::shared_int robot_id_;
00310   industrial::shared_types::shared_int valid_fields_;
00315   industrial::shared_types::shared_real time_;
00316 
00320   industrial::joint_data::JointData positions_;
00324   industrial::joint_data::JointData velocities_;  
00327   industrial::joint_data::JointData accelerations_;
00328 
00329 };
00330 
00331 }
00332 }
00333 
00334 #endif /* JOINT_FEEDBACK_H */


simple_message
Author(s): Shaun Edwards
autogenerated on Fri Aug 28 2015 11:11:56