joint_traj_pt_full_ex.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014, Fraunhofer IPA
5  * Author: Thiago de Freitas
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the Fraunhofer IPA, nor the names
18  * of its contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #include <vector>
35 
36 #ifndef FLATHEADERS
41 #else
42 #include "joint_traj_pt_full_ex.h" // NOLINT(build/include)
43 #include "joint_traj_pt_full.h" // NOLINT(build/include)
44 #include "shared_types.h" // NOLINT(build/include)
45 #include "log_wrapper.h" // NOLINT(build/include)
46 #endif
47 
50 
51 namespace industrial
52 {
53 namespace joint_traj_pt_full_ex
54 {
55 
57 {
58  this->init();
59 }
61 {
62 }
63 
65 {
67  this->sequence_ = 0;
68 
69  for (int i = 0; i < MAX_NUM_GROUPS; i++)
70  {
71  JointTrajPtFull joint_traj_pt_full;
72 
73  joint_traj_pt_full.init();
74 
75  this->joint_trajectory_points_.push_back(joint_traj_pt_full);
76  }
77 }
78 
81  std::vector<industrial::joint_traj_pt_full::JointTrajPtFull> joint_trajectory_points)
82 {
83  this->setNumGroups(num_groups);
84  this->setSequence(sequence);
86 }
87 
89 {
90  this->setNumGroups(src.num_groups_);
91  this->setSequence(src.sequence_);
93 }
94 
96 {
97  // TODO(thiagodefreitas): expand the capabilities of this check
98  return this->num_groups_ == rhs.num_groups_;
99 }
100 
102 {
103  LOG_COMM("Executing joint trajectory point load");
104 
105  if (!buffer->load(this->num_groups_))
106  {
107  LOG_ERROR("Failed to load joint traj pt. robot_id");
108  return false;
109  }
110 
111  if (!buffer->load(this->sequence_))
112  {
113  LOG_ERROR("Failed to load joint traj. pt. sequence number");
114  return false;
115  }
116 
117  for (size_t i = 0; i < joint_trajectory_points_.size(); i++)
118  {
120 
121  if (!buffer->load(traj_full.getRobotID()))
122  {
123  LOG_ERROR("Failed to load joint traj pt. robot_id");
124  return false;
125  }
126 
128  if (traj_full.getPositions(positions))
129  this->valid_fields_from_message_ |= ValidFieldTypes::POSITION;
130  else
131  this->valid_fields_from_message_ &= ~ValidFieldTypes::POSITION;
132 
134  if (traj_full.getVelocities(velocities))
135  this->valid_fields_from_message_ |= ValidFieldTypes::VELOCITY;
136  else
137  this->valid_fields_from_message_ &= ~ValidFieldTypes::VELOCITY;
138 
139  industrial::joint_data::JointData accelerations;
140  if (traj_full.getAccelerations(accelerations))
141  this->valid_fields_from_message_ |= ValidFieldTypes::ACCELERATION;
142  else
143  this->valid_fields_from_message_ &= ~ValidFieldTypes::ACCELERATION;
144 
146  if (traj_full.getTime(this_time))
147  this->valid_fields_from_message_ |= ValidFieldTypes::TIME;
148  else
150 
151  if (!buffer->load(valid_fields_from_message_))
152  {
153  LOG_ERROR("Failed to load joint traj. pt. valid fields");
154  return false;
155  }
156 
157  if (!buffer->load(this_time))
158  {
159  LOG_ERROR("Failed to load joint traj. pt. time");
160  return false;
161  }
162 
164 
165  for (int j = 0; j < positions.getMaxNumJoints(); j++)
166  {
167  pos = positions.getJoint(j);
168  if (!buffer->load(pos))
169  {
170  LOG_ERROR("Failed to load joint traj. pt. positions");
171  return false;
172  }
173  }
174 
176 
177  for (int j = 0; j < velocities.getMaxNumJoints(); j++)
178  {
179  vel = velocities.getJoint(j);
180  if (!buffer->load(vel))
181  {
182  LOG_ERROR("Failed to load joint traj. pt. positions");
183  return false;
184  }
185  }
186 
188 
189  for (int j = 0; j < accelerations.getMaxNumJoints(); j++)
190  {
191  acc = accelerations.getJoint(j);
192  if (!buffer->load(acc))
193  {
194  LOG_ERROR("Failed to load joint traj. pt. positions");
195  return false;
196  }
197  }
198 
199  LOG_COMM("Trajectory point successfully loaded");
200  }
201  LOG_COMM("Trajectory point successfully loaded");
202  return true;
203 }
204 
206 {
207  LOG_COMM("Executing joint traj. pt. unload");
208 
209  for (size_t i = 0; i < joint_trajectory_points_.size(); i++)
210  {
211  if (!buffer->unload(joint_trajectory_points_[i]))
212  {
213  LOG_ERROR("Failed to unload joint traj. pt.");
214  return false;
215  }
216  }
217  if (!buffer->unload(this->sequence_))
218  {
219  LOG_ERROR("Failed to unload joint traj. pt. sequence number");
220  return false;
221  }
222 
223  if (!buffer->unload(this->num_groups_))
224  {
225  LOG_ERROR("Faild to unload joint traj. pt. num_groups");
226  return false;
227  }
228  LOG_COMM("Joint traj. pt successfully unloaded");
229  return true;
230 }
231 
232 } // namespace joint_traj_pt_full_ex
233 } // namespace industrial
234 
235 
industrial::shared_types::shared_int valid_fields_from_message_
float pos[ROS_MAX_JOINT]
float acc[ROS_MAX_JOINT]
Class encapsulated joint trajectory point data. The point data serves as a waypoint along a trajector...
bool getTime(industrial::shared_types::shared_real &time)
bool load(industrial::byte_array::ByteArray *buffer)
int sequence
void setSequence(industrial::shared_types::shared_int sequence)
Sets joint trajectory point sequence number.
bool operator==(JointTrajPtFullEx &rhs)
== operator implementation
#define LOG_COMM(format,...)
std::vector< industrial::joint_traj_pt_full::JointTrajPtFull > joint_trajectory_points_
bool load(industrial::shared_types::shared_bool value)
#define LOG_ERROR(format,...)
bool getJoint(industrial::shared_types::shared_int index, industrial::shared_types::shared_real &value) const
industrial::shared_types::shared_int getRobotID()
bool getPositions(industrial::joint_data::JointData &dest)
void setNumGroups(industrial::shared_types::shared_int num_groups)
Sets num_groups Number of groups attached to the controller.
bool unload(industrial::byte_array::ByteArray *buffer)
static const industrial::shared_types::shared_int MAX_NUM_GROUPS
void setMultiJointTrajPtData(std::vector< industrial::joint_traj_pt_full::JointTrajPtFull > joint_trajectory_points)
industrial::shared_types::shared_int num_groups_
number of groups for controllers that support multiple axis-groups
bool getAccelerations(industrial::joint_data::JointData &dest)
bool unload(industrial::shared_types::shared_bool &value)
void copyFrom(JointTrajPtFullEx &src)
Copies the passed in value.
void init()
Initializes a empty joint trajectory group.
industrial::shared_types::shared_int sequence_
trajectory sequence number
float vel[ROS_MAX_JOINT]
bool getVelocities(industrial::joint_data::JointData &dest)


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:43