joint_traj_pt_full.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_TRAJ_PT_FULL_H
00033 #define JOINT_TRAJ_PT_FULL_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_traj_pt_full
00050 {
00051 
00052 namespace SpecialSeqValues
00053 {
00054 enum SpecialSeqValue
00055 {
00056   START_TRAJECTORY_DOWNLOAD  = -1, 
00057   START_TRAJECOTRY_STREAMING = -2, 
00058   START_TRAJECTORY_STREAMING = -2, 
00059   END_TRAJECTORY  = -3, 
00060   STOP_TRAJECTORY = -4  
00061 };
00062 }
00063 typedef SpecialSeqValues::SpecialSeqValue SpecialSeqValue;
00064 
00065 namespace ValidFieldTypes
00066 {
00067 enum ValidFieldType
00068 {
00069   TIME = 0x01, POSITION = 0x02, VELOCITY = 0x04, ACCELERATION = 0x08
00070 };
00071 }
00072 typedef ValidFieldTypes::ValidFieldType ValidFieldType;
00073 
00100 class JointTrajPtFull : public industrial::simple_serialize::SimpleSerialize
00101 {
00102 public:
00103 
00110   JointTrajPtFull(void);
00115   ~JointTrajPtFull(void);
00116 
00121   void init();
00122 
00127   void init(industrial::shared_types::shared_int robot_id,
00128             industrial::shared_types::shared_int sequence,
00129             industrial::shared_types::shared_int valid_fields,
00130             industrial::shared_types::shared_real time,
00131             industrial::joint_data::JointData & positions,
00132             industrial::joint_data::JointData & velocities,
00133             industrial::joint_data::JointData & accelerations);
00134 
00141   void setRobotID(industrial::shared_types::shared_int robot_id)
00142   {
00143     this->robot_id_ = robot_id;
00144   }
00145 
00152   industrial::shared_types::shared_int getRobotID()
00153   {
00154     return this->robot_id_;
00155   }
00156 
00162   void setSequence(industrial::shared_types::shared_int sequence)
00163   {
00164     this->sequence_ = sequence;
00165   }
00166 
00172   industrial::shared_types::shared_int getSequence()
00173   {
00174     return this->sequence_;
00175   }
00176 
00182   void setTime(industrial::shared_types::shared_real time)
00183   {
00184     this->time_ = time;
00185     this->valid_fields_ |= ValidFieldTypes::TIME;  // set the bit
00186   }
00187 
00194   bool getTime(industrial::shared_types::shared_real & time)
00195   {
00196     time = this->time_;
00197     return is_valid(ValidFieldTypes::TIME);
00198   }
00199 
00203   void clearTime()
00204   {
00205     this->time_ = 0;
00206     this->valid_fields_ &= ~ValidFieldTypes::TIME;  // clear the bit
00207   }
00208 
00214   void setPositions(industrial::joint_data::JointData &positions)
00215   {
00216     this->positions_.copyFrom(positions);
00217     this->valid_fields_ |= ValidFieldTypes::POSITION;  // set the bit
00218   }
00219 
00226   bool getPositions(industrial::joint_data::JointData &dest)
00227   {
00228     dest.copyFrom(this->positions_);
00229     return is_valid(ValidFieldTypes::POSITION);
00230   }
00231 
00235   void clearPositions()
00236   {
00237     this->positions_.init();
00238     this->valid_fields_ &= ~ValidFieldTypes::POSITION;  // clear the bit
00239   }
00240 
00246   void setVelocities(industrial::joint_data::JointData &velocities)
00247   {
00248     this->velocities_.copyFrom(velocities);
00249     this->valid_fields_ |= ValidFieldTypes::VELOCITY;  // set the bit
00250   }
00251 
00258   bool getVelocities(industrial::joint_data::JointData &dest)
00259   {
00260     dest.copyFrom(this->velocities_);
00261     return is_valid(ValidFieldTypes::VELOCITY);
00262   }
00263 
00267   void clearVelocities()
00268   {
00269     this->velocities_.init();
00270     this->valid_fields_ &= ~ValidFieldTypes::VELOCITY;  // clear the bit
00271   }
00277   void setAccelerations(industrial::joint_data::JointData &accelerations)
00278   {
00279     this->accelerations_.copyFrom(accelerations);
00280     this->valid_fields_ |= ValidFieldTypes::ACCELERATION;  // set the bit
00281   }
00282 
00289   bool getAccelerations(industrial::joint_data::JointData &dest)
00290   {
00291     dest.copyFrom(this->accelerations_);
00292     return is_valid(ValidFieldTypes::ACCELERATION);
00293   }
00294 
00298   void clearAccelerations()
00299   {
00300     this->accelerations_.init();
00301     this->valid_fields_ &= ~ValidFieldTypes::ACCELERATION;  // clear the bit
00302   }
00303 
00304 
00310   void copyFrom(JointTrajPtFull &src);
00311 
00317   bool operator==(JointTrajPtFull &rhs);
00318 
00324   bool is_valid(ValidFieldType field)
00325   {
00326     return valid_fields_ & field;
00327   }
00328 
00329   // Overrides - SimpleSerialize
00330   bool load(industrial::byte_array::ByteArray *buffer);
00331   bool unload(industrial::byte_array::ByteArray *buffer);
00332   unsigned int byteLength()
00333   {
00334     return 3*sizeof(industrial::shared_types::shared_int) + sizeof(industrial::shared_types::shared_real)
00335         + 3*this->positions_.byteLength();
00336   }
00337 
00338 private:
00339 
00343   industrial::shared_types::shared_int robot_id_;
00347   industrial::shared_types::shared_int sequence_;
00352   industrial::shared_types::shared_int valid_fields_;
00357   industrial::shared_types::shared_real time_;
00358 
00362   industrial::joint_data::JointData positions_;
00366   industrial::joint_data::JointData velocities_;  
00369   industrial::joint_data::JointData accelerations_;
00370 
00371 };
00372 
00373 }
00374 }
00375 
00376 #endif /* JOINT_TRAJ_PT_FULL_H */


simple_message
Author(s): Shaun Edwards
autogenerated on Tue Jan 17 2017 21:10:02