joint_traj_pt_full_ex.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2014, Fraunhofer IPA
00005  * Author: Thiago de Freitas
00006  *
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions are met:
00011  *
00012  *  * Redistributions of source code must retain the above copyright
00013  *  notice, this list of conditions and the following disclaimer.
00014  *  * Redistributions in binary form must reproduce the above copyright
00015  *  notice, this list of conditions and the following disclaimer in the
00016  *  documentation and/or other materials provided with the distribution.
00017  *  * Neither the name of the Fraunhofer IPA, nor the names
00018  *  of its contributors may be used to endorse or promote products derived
00019  *  from this software without specific prior written permission.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00023  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00024  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00025  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00026  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00027  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00028  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00029  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00030  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031  * POSSIBILITY OF SUCH DAMAGE.
00032  */
00033 
00034 #ifndef MOTOMAN_DRIVER_SIMPLE_MESSAGE_JOINT_TRAJ_PT_FULL_EX_H
00035 #define MOTOMAN_DRIVER_SIMPLE_MESSAGE_JOINT_TRAJ_PT_FULL_EX_H
00036 
00037 #ifndef FLATHEADERS
00038 #include "simple_message/joint_data.h"
00039 #include "simple_message/simple_message.h"
00040 #include "simple_message/simple_serialize.h"
00041 #include "simple_message/shared_types.h"
00042 #include "simple_message/joint_traj_pt_full.h"
00043 #else
00044 #include "joint_data.h"
00045 #include "simple_message.h"
00046 #include "simple_serialize.h"
00047 #include "shared_types.h"
00048 #endif
00049 
00050 #include<vector>
00051 namespace industrial
00052 {
00053 namespace joint_traj_pt_full_ex
00054 {
00055 
00056 namespace SpecialSeqValues
00057 {
00058 enum SpecialSeqValue
00059 {
00060   START_TRAJECTORY_DOWNLOAD = -1, START_TRAJECOTRY_STREAMING = -2, END_TRAJECTORY = -3, STOP_TRAJECTORY = -4
00061 };
00062 }
00063 typedef SpecialSeqValues::SpecialSeqValue SpecialSeqValue;
00064 
00086 class JointTrajPtFullEx : public industrial::simple_serialize::SimpleSerialize
00087 {
00088 public:
00095   JointTrajPtFullEx(void);
00100   ~JointTrajPtFullEx(void);
00101 
00106   void init();
00107 
00112   void init(industrial::shared_types::shared_int num_groups,
00113             industrial::shared_types::shared_int sequence,
00114             std::vector<industrial::joint_traj_pt_full::JointTrajPtFull> joint_trajectory_points);
00115 
00122   void setNumGroups(industrial::shared_types::shared_int num_groups)
00123   {
00124     this->num_groups_ = num_groups;
00125   }
00126 
00134   industrial::shared_types::shared_int getNumGroups()
00135   {
00136     return this->num_groups_;
00137   }
00138 
00139   void setMultiJointTrajPtData(std::vector<industrial::joint_traj_pt_full::JointTrajPtFull> joint_trajectory_points)
00140   {
00141     this->joint_trajectory_points_ = joint_trajectory_points;
00142   }
00143 
00149   void setSequence(industrial::shared_types::shared_int sequence)
00150   {
00151     this->sequence_ = sequence;
00152   }
00153 
00160   industrial::shared_types::shared_int getMaxGroups()
00161   {
00162     return MAX_NUM_GROUPS;
00163   }
00164 
00171   industrial::shared_types::shared_int getSequence()
00172   {
00173     return this->sequence_;
00174   }
00175 
00181   void copyFrom(JointTrajPtFullEx &src);
00182 
00188   bool operator==(JointTrajPtFullEx &rhs);
00189 
00190 
00191   // Overrides - SimpleSerialize
00192   bool load(industrial::byte_array::ByteArray *buffer);
00193   bool unload(industrial::byte_array::ByteArray *buffer);
00194   unsigned int byteLength()
00195   {
00196     return sizeof(industrial::shared_types::shared_int) + sizeof(industrial::shared_types::shared_int) + MAX_NUM_GROUPS * (this->joint_traj_full_sample_.byteLength() - sizeof(industrial::shared_types::shared_int));
00197   }
00198 
00199 private:
00200   std::vector<industrial::joint_traj_pt_full::JointTrajPtFull> joint_trajectory_points_;
00201 
00202   industrial::joint_traj_pt_full::JointTrajPtFull joint_traj_full_sample_;
00206   industrial::shared_types::shared_int num_groups_;
00210   industrial::shared_types::shared_int sequence_;
00211 
00212   industrial::shared_types::shared_int valid_fields_from_message_;
00213 
00214   static const industrial::shared_types::shared_int MAX_NUM_GROUPS = 4;
00215 };
00216 }  // namespace joint_traj_pt_full_ex
00217 }  // namespace industrial
00218 
00219 #endif  // MOTOMAN_DRIVER_SIMPLE_MESSAGE_JOINT_TRAJ_PT_FULL_EX_H


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:57