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 #include <vector> 00035 00036 #ifndef FLATHEADERS 00037 #include "motoman_driver/simple_message/joint_traj_pt_full_ex.h" 00038 #include "simple_message/joint_traj_pt_full.h" 00039 #include "simple_message/shared_types.h" 00040 #include "simple_message/log_wrapper.h" 00041 #else 00042 #include "joint_traj_pt_full_ex.h" 00043 #include "joint_traj_pt_full.h" 00044 #include "shared_types.h" 00045 #include "log_wrapper.h" 00046 #endif 00047 00048 using industrial::joint_traj_pt_full::JointTrajPtFull; 00049 namespace ValidFieldTypes = industrial::joint_traj_pt_full::ValidFieldTypes; 00050 00051 namespace industrial 00052 { 00053 namespace joint_traj_pt_full_ex 00054 { 00055 00056 JointTrajPtFullEx::JointTrajPtFullEx(void) 00057 { 00058 this->init(); 00059 } 00060 JointTrajPtFullEx::~JointTrajPtFullEx(void) 00061 { 00062 } 00063 00064 void JointTrajPtFullEx::init() 00065 { 00066 this->num_groups_ = MAX_NUM_GROUPS; 00067 this->sequence_ = 0; 00068 00069 for (int i = 0; i < MAX_NUM_GROUPS; i++) 00070 { 00071 JointTrajPtFull joint_traj_pt_full; 00072 00073 joint_traj_pt_full.init(); 00074 00075 this->joint_trajectory_points_.push_back(joint_traj_pt_full); 00076 } 00077 } 00078 00079 void JointTrajPtFullEx::init(industrial::shared_types::shared_int num_groups, 00080 industrial::shared_types::shared_int sequence, 00081 std::vector<industrial::joint_traj_pt_full::JointTrajPtFull> joint_trajectory_points) 00082 { 00083 this->setNumGroups(num_groups); 00084 this->setSequence(sequence); 00085 this->setMultiJointTrajPtData(joint_trajectory_points_); 00086 } 00087 00088 void JointTrajPtFullEx::copyFrom(JointTrajPtFullEx &src) 00089 { 00090 this->setNumGroups(src.num_groups_); 00091 this->setSequence(src.sequence_); 00092 this->setMultiJointTrajPtData(src.joint_trajectory_points_); 00093 } 00094 00095 bool JointTrajPtFullEx::operator==(JointTrajPtFullEx &rhs) 00096 { 00097 // TODO(thiagodefreitas): expand the capabilities of this check 00098 return this->num_groups_ == rhs.num_groups_; 00099 } 00100 00101 bool JointTrajPtFullEx::load(industrial::byte_array::ByteArray *buffer) 00102 { 00103 LOG_COMM("Executing joint trajectory point load"); 00104 00105 if (!buffer->load(this->num_groups_)) 00106 { 00107 LOG_ERROR("Failed to load joint traj pt. robot_id"); 00108 return false; 00109 } 00110 00111 if (!buffer->load(this->sequence_)) 00112 { 00113 LOG_ERROR("Failed to load joint traj. pt. sequence number"); 00114 return false; 00115 } 00116 00117 for (int i = 0; i < joint_trajectory_points_.size(); i++) 00118 { 00119 JointTrajPtFull traj_full = joint_trajectory_points_[i]; 00120 00121 if (!buffer->load(traj_full.getRobotID())) 00122 { 00123 LOG_ERROR("Failed to load joint traj pt. robot_id"); 00124 return false; 00125 } 00126 00127 industrial::joint_data::JointData positions; 00128 if (traj_full.getPositions(positions)) 00129 this->valid_fields_from_message_ |= ValidFieldTypes::POSITION; 00130 else 00131 this->valid_fields_from_message_ &= ~ValidFieldTypes::POSITION; 00132 00133 industrial::joint_data::JointData velocities; 00134 if (traj_full.getVelocities(velocities)) 00135 this->valid_fields_from_message_ |= ValidFieldTypes::VELOCITY; 00136 else 00137 this->valid_fields_from_message_ &= ~ValidFieldTypes::VELOCITY; 00138 00139 industrial::joint_data::JointData accelerations; 00140 if (traj_full.getAccelerations(accelerations)) 00141 this->valid_fields_from_message_ |= ValidFieldTypes::ACCELERATION; 00142 else 00143 this->valid_fields_from_message_ &= ~ValidFieldTypes::ACCELERATION; 00144 00145 industrial::shared_types::shared_real this_time; 00146 if (traj_full.getTime(this_time)) 00147 this->valid_fields_from_message_ |= ValidFieldTypes::TIME; 00148 else 00149 this->valid_fields_from_message_ &= ~ValidFieldTypes::TIME; 00150 00151 if (!buffer->load(valid_fields_from_message_)) 00152 { 00153 LOG_ERROR("Failed to load joint traj. pt. valid fields"); 00154 return false; 00155 } 00156 00157 if (!buffer->load(this_time)) 00158 { 00159 LOG_ERROR("Failed to load joint traj. pt. time"); 00160 return false; 00161 } 00162 00163 industrial::shared_types::shared_real pos; 00164 00165 for (int j = 0; j < positions.getMaxNumJoints(); j++) 00166 { 00167 pos = positions.getJoint(j); 00168 if (!buffer->load(pos)) 00169 { 00170 LOG_ERROR("Failed to load joint traj. pt. positions"); 00171 return false; 00172 } 00173 } 00174 00175 industrial::shared_types::shared_real vel; 00176 00177 for (int j = 0; j < velocities.getMaxNumJoints(); j++) 00178 { 00179 vel = velocities.getJoint(j); 00180 if (!buffer->load(vel)) 00181 { 00182 LOG_ERROR("Failed to load joint traj. pt. positions"); 00183 return false; 00184 } 00185 } 00186 00187 industrial::shared_types::shared_real acc; 00188 00189 for (int j = 0; j < accelerations.getMaxNumJoints(); j++) 00190 { 00191 acc = accelerations.getJoint(j); 00192 if (!buffer->load(acc)) 00193 { 00194 LOG_ERROR("Failed to load joint traj. pt. positions"); 00195 return false; 00196 } 00197 } 00198 00199 LOG_COMM("Trajectory point successfully loaded"); 00200 } 00201 LOG_COMM("Trajectory point successfully loaded"); 00202 return true; 00203 } 00204 00205 bool JointTrajPtFullEx::unload(industrial::byte_array::ByteArray *buffer) 00206 { 00207 LOG_COMM("Executing joint traj. pt. unload"); 00208 00209 for (int i = 0; i < joint_trajectory_points_.size(); i++) 00210 { 00211 if (!buffer->unload(joint_trajectory_points_[i])) 00212 { 00213 LOG_ERROR("Failed to unload joint traj. pt."); 00214 return false; 00215 } 00216 } 00217 if (!buffer->unload(this->sequence_)) 00218 { 00219 LOG_ERROR("Failed to unload joint traj. pt. sequence number"); 00220 return false; 00221 } 00222 00223 if (!buffer->unload(this->num_groups_)) 00224 { 00225 LOG_ERROR("Faild to unload joint traj. pt. num_groups"); 00226 return false; 00227 } 00228 LOG_COMM("Joint traj. pt successfully unloaded"); 00229 return true; 00230 } 00231 00232 } // namespace joint_traj_pt_full_ex 00233 } // namespace industrial 00234 00235