eff_box.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019, Christopher E. Mower
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #include <exotica_core/server.h>
32 
34 
35 namespace exotica
36 {
38 {
39  if (phi.rows() != TaskSpaceDim()) ThrowNamed("Wrong size of phi!");
40 
41  for (int i = 0; i < n_effs_; ++i)
42  {
43  // Setup
44  const int eff_id = 3 * i;
45 
46  // Compute phi
47  phi.segment(eff_id, 3) = Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data) - eff_upper_.segment<3>(eff_id);
48  phi.segment(eff_id + three_times_n_effs_, 3) = eff_lower_.segment<3>(eff_id) - Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data);
49  }
50 
52 }
53 
55 {
56  if (phi.rows() != TaskSpaceDim()) ThrowNamed("Wrong size of phi!");
57  if (jacobian.rows() != TaskSpaceDim() || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
58 
59  for (int i = 0; i < n_effs_; ++i)
60  {
61  // Setup
62  const int eff_id = 3 * i;
63 
64  // Compute phi and jacobian
65  phi.segment(eff_id, 3) = Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data) - eff_upper_.segment<3>(eff_id);
66  phi.segment(eff_id + three_times_n_effs_, 3) = eff_lower_.segment<3>(eff_id) - Eigen::Map<Eigen::Vector3d>(kinematics[0].Phi(i).p.data);
67  jacobian.middleRows(eff_id, 3) = kinematics[0].jacobian(i).data.topRows<3>();
68  jacobian.middleRows(eff_id + three_times_n_effs_, 3) = -kinematics[0].jacobian(i).data.topRows<3>();
69  }
70 
72 }
73 
74 Eigen::Vector3d EffBox::GetLowerLimit(const int eff_id) const
75 {
76  if (eff_id < 0 || eff_id >= n_effs_) ThrowNamed("Given eff_id (" << eff_id << ") is out of range [0, " << n_effs_ << ")!");
77  return eff_lower_.segment<3>(3 * eff_id);
78 }
79 
80 Eigen::Vector3d EffBox::GetUpperLimit(const int eff_id) const
81 {
82  if (eff_id < 0 || eff_id >= n_effs_) ThrowNamed("Given eff_id (" << eff_id << ") is out of range [0, " << n_effs_ << ")!");
83  return eff_upper_.segment<3>(3 * eff_id);
84 }
85 
87 {
88  const ros::Time t = ros::Time::now();
89  visualization_msgs::MarkerArray ma;
90  ma.markers.reserve(n_effs_);
91  for (int i = 0; i < n_effs_; ++i)
92  {
93  const int eff_id = 3 * i;
94  visualization_msgs::Marker m;
95  m.header.stamp = t;
96  std::string frame_name;
97  if (frames_[i].frame_B_link_name == "")
98  {
99  frame_name = scene_->GetRootFrameName();
100  }
101  else
102  {
103  frame_name = frames_[i].frame_B_link_name;
104  }
105  m.header.frame_id = "exotica/" + frame_name;
106  m.id = i;
107  m.action = visualization_msgs::Marker::ADD;
108  m.type = visualization_msgs::Marker::CUBE;
109  m.scale.x = eff_upper_(eff_id) - eff_lower_(eff_id);
110  m.scale.y = eff_upper_(eff_id + 1) - eff_lower_(eff_id + 1);
111  m.scale.z = eff_upper_(eff_id + 2) - eff_lower_(eff_id + 2);
112  m.pose.position.x = (eff_upper_(eff_id) + eff_lower_(eff_id)) / 2.0;
113  m.pose.position.y = (eff_upper_(eff_id + 1) + eff_lower_(eff_id + 1)) / 2.0;
114  m.pose.position.z = (eff_upper_(eff_id + 2) + eff_lower_(eff_id + 2)) / 2.0;
115  m.pose.orientation.w = 1.0;
116  m.color.r = 1.0;
117  m.color.a = 0.25;
118  ma.markers.emplace_back(m);
119  }
120  pub_markers_.publish(ma);
121 }
122 
123 void EffBox::Instantiate(const EffBoxInitializer& init)
124 {
125  parameters_ = init;
126  n_effs_ = frames_.size();
128 
129  // Populate eff_upper_ and eff_lower_
130  eff_upper_.resize(3 * n_effs_, 1);
131  eff_lower_.resize(3 * n_effs_, 1);
132 
133  for (int i = 0; i < n_effs_; ++i)
134  {
135  const int eff_id = 3 * i;
136 
137  // Initialize frame and check user input
138  FrameWithBoxLimitsInitializer frame(parameters_.EndEffector[i]);
139  if (frame.XLim[0] > frame.XLim[1]) ThrowPretty("Specify XLim using lower then upper for end-effector " << i << ".");
140  if (frame.YLim[0] > frame.YLim[1]) ThrowPretty("Specify YLim using lower then upper for end-effector " << i << ".");
141  if (frame.ZLim[0] > frame.ZLim[1]) ThrowPretty("Specify ZLim using lower then upper for end-effector " << i << ".");
142 
143  // Set upper and lower limits
144  eff_upper_[eff_id] = frame.XLim[1];
145  eff_upper_[eff_id + 1] = frame.YLim[1];
146  eff_upper_[eff_id + 2] = frame.ZLim[1];
147 
148  eff_lower_[eff_id] = frame.XLim[0];
149  eff_lower_[eff_id + 1] = frame.YLim[0];
150  eff_lower_[eff_id + 2] = frame.ZLim[0];
151  }
152 
153  if (debug_ && Server::IsRos())
154  {
155  pub_markers_ = Server::Advertise<visualization_msgs::MarkerArray>("eff_box_objects", 1, true);
156  visualization_msgs::Marker md; // delete previous markers
157  md.action = 3; // DELETEALL
158  visualization_msgs::MarkerArray ma;
159  ma.markers.reserve(1);
160  ma.markers.emplace_back(md);
161  pub_markers_.publish(ma);
162  }
163 }
164 
166 {
167  return 6 * n_effs_;
168 }
169 } // namespace exotica
exotica::EffBox::n_effs_
int n_effs_
Number of end-effectors.
Definition: eff_box.h:61
exotica::Instantiable< EffBoxInitializer >::parameters_
C parameters_
exotica::EffBox::Update
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
Definition: eff_box.cpp:37
exotica::EffBox::eff_lower_
Eigen::VectorXd eff_lower_
End-effector lower x, y, z limit.
Definition: eff_box.h:59
exotica::EffBox
Limits every given end-effector motion to a box in some reference frame.
Definition: eff_box.h:45
exotica::EffBox::eff_upper_
Eigen::VectorXd eff_upper_
End-effector upper x, y, z limit.
Definition: eff_box.h:60
exotica::EffBox::PublishObjectsAsMarkerArray
void PublishObjectsAsMarkerArray()
Definition: eff_box.cpp:86
exotica::EffBox::GetLowerLimit
Eigen::Vector3d GetLowerLimit(const int eff_id) const
Definition: eff_box.cpp:74
exotica::EffBox::TaskSpaceDim
int TaskSpaceDim() override
Definition: eff_box.cpp:165
exotica
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
REGISTER_TASKMAP_TYPE
REGISTER_TASKMAP_TYPE("EffBox", exotica::EffBox)
exotica::EffBox::Instantiate
void Instantiate(const EffBoxInitializer &init) override
Definition: eff_box.cpp:123
exotica::EffBox::GetUpperLimit
Eigen::Vector3d GetUpperLimit(const int eff_id) const
Definition: eff_box.cpp:80
Eigen::VectorXdRef
Eigen::Ref< Eigen::VectorXd > VectorXdRef
Eigen::VectorXdRefConst
const typedef Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
kinematics
exotica::TaskMap::scene_
ScenePtr scene_
Eigen::MatrixXdRef
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
exotica::Object::debug_
bool debug_
eff_box.h
exotica::EffBox::three_times_n_effs_
int three_times_n_effs_
Definition: eff_box.h:62
ros::Time
ThrowPretty
#define ThrowPretty(m)
exotica::TaskMap::frames_
std::vector< KinematicFrameRequest > frames_
init
void init(const M_string &remappings)
exotica::EffBox::pub_markers_
ros::Publisher pub_markers_
Three multiplied by the number of end-effectors.
Definition: eff_box.h:63
server.h
exotica::Server::IsRos
static bool IsRos()
t
geometry_msgs::TransformStamped t
ThrowNamed
#define ThrowNamed(m)
ros::Time::now
static Time now()


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Aug 2 2024 08:44:10