avoid_look_at_sphere.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  for (int i = 0; i < n_objects_; ++i)
40  {
41  const double frac = Eigen::Map<Eigen::Vector2d>(kinematics[0].Phi(i).p.data).squaredNorm() / radii_squared_(i);
42  if (frac < 1.0)
43  {
44  phi(i) = 1.0 - 2.0 * frac + frac * frac;
45  }
46  else
47  {
48  phi(i) = 0.0;
49  }
50  }
51 }
52 
54 {
55  for (int i = 0; i < n_objects_; ++i) phi(i) = radii_squared_(i) - Eigen::Map<Eigen::Vector2d>(kinematics[0].Phi(i).p.data).squaredNorm();
56 }
57 
59 {
60  for (int i = 0; i < n_objects_; ++i)
61  {
62  Eigen::Vector2d o = Eigen::Map<Eigen::Vector2d>(kinematics[0].Phi(i).p.data);
63  const double frac = o.squaredNorm() / radii_squared_(i);
64  if (frac < 1.0)
65  {
66  phi(i) = 1.0 - 2.0 * frac + frac * frac;
67  for (int j = 0; j < jacobian.cols(); ++j) jacobian(i, j) = -4.0 * (1.0 - frac) * kinematics[0].jacobian[i].data.topRows<2>().col(j).dot(o) / radii_squared_(i);
68  }
69  else
70  {
71  phi(i) = 0.0;
72  jacobian.row(i).setZero();
73  }
74  }
75 }
76 
78 {
79  for (int i = 0; i < n_objects_; ++i)
80  {
81  Eigen::Vector2d o = Eigen::Map<Eigen::Vector2d>(kinematics[0].Phi(i).p.data);
82  const double d = o.norm();
83  phi(i) = radii_squared_(i) - d * d;
84  for (int j = 0; j < jacobian.cols(); ++j) jacobian(i, j) = -2.0 * kinematics[0].jacobian[i].data.topRows<2>().col(j).dot(o);
85  }
86 }
87 
89 {
90  const ros::Time t = ros::Time::now();
91  visualization_msgs::MarkerArray ma;
92  ma.markers.reserve(n_objects_);
93  for (int i = 0; i < n_objects_; ++i)
94  {
95  visualization_msgs::Marker m;
96  m.header.stamp = t;
97  m.header.frame_id = "exotica/" + frames_[i].frame_B_link_name;
98  m.id = i;
99  m.action = visualization_msgs::Marker::ADD;
100  m.type = visualization_msgs::Marker::SPHERE;
101  m.scale.x = diameter_(i);
102  m.scale.y = diameter_(i);
103  m.scale.z = diameter_(i);
104  Eigen::Vector4d q = GetRotationAsVector(kinematics[0].Phi(i), RotationType::QUATERNION);
105  m.pose.position.x = kinematics[0].Phi(i).p.data[0];
106  m.pose.position.y = kinematics[0].Phi(i).p.data[1];
107  m.pose.position.z = kinematics[0].Phi(i).p.data[2];
108  m.pose.orientation.x = q[0];
109  m.pose.orientation.y = q[1];
110  m.pose.orientation.z = q[2];
111  m.pose.orientation.w = q[3];
112  m.color.r = 1.0;
113  m.color.a = 1.0;
114  ma.markers.emplace_back(m);
115  }
116  pub_markers_.publish(ma);
117 }
118 
120 {
121  (this->*UpdateTaskMapWithoutJacobian)(x, phi);
123 }
124 
126 {
127  (this->*UpdateTaskMapWithJacobian)(x, phi, jacobian);
129 }
130 
131 void AvoidLookAtSphere::Instantiate(const AvoidLookAtSphereInitializer& init)
132 {
133  parameters_ = init;
134  n_objects_ = frames_.size();
135  diameter_.resize(n_objects_, 1);
136  radii_squared_.resize(n_objects_, 1);
137 
138  for (int i = 0; i < n_objects_; ++i)
139  {
140  SphereInitializer sphere(init.EndEffector[i]);
141  diameter_(i) = 2.0 * sphere.Radius;
142  radii_squared_(i) = sphere.Radius * sphere.Radius;
143  }
144 
145  if (init.UseAsCost)
146  {
149  }
150  else
151  {
154  }
155 
156  if (debug_ && Server::IsRos())
157  {
158  pub_markers_ = Server::Advertise<visualization_msgs::MarkerArray>("avoid_look_at_sphere_objects", 1, true);
159  visualization_msgs::Marker md; // delete previous markers
160  md.action = visualization_msgs::Marker::DELETEALL;
161  visualization_msgs::MarkerArray ma;
162  ma.markers.push_back(md);
163  pub_markers_.publish(ma);
164  }
165 }
166 
168 {
169  return n_objects_;
170 }
171 } // namespace exotica
d
void(AvoidLookAtSphere::* UpdateTaskMapWithJacobian)(Eigen::VectorXdRefConst, Eigen::VectorXdRef, Eigen::MatrixXdRef)
void publish(const boost::shared_ptr< M > &message) const
std::vector< KinematicFrameRequest > frames_
void UpdateAsInequalityConstraintWithJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian)
Eigen::VectorXd radii_squared_
The square of each object radii.
Eigen::Ref< Eigen::VectorXd > VectorXdRef
void Instantiate(const AvoidLookAtSphereInitializer &init) override
void UpdateAsCostWithJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi, Eigen::MatrixXdRef jacobian)
REGISTER_TASKMAP_TYPE("AvoidLookAtSphere", exotica::AvoidLookAtSphere)
void UpdateAsCostWithoutJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi)
ros::Publisher pub_markers_
publish marker for RViz
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
void UpdateAsInequalityConstraintWithoutJacobian(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi)
Avoids pointing end-effector at a given spherical object.
Eigen::VectorXd diameter_
The diameter of each object.
int n_objects_
Number of spherical objects.
static Time now()
Eigen::VectorXd GetRotationAsVector(const KDL::Frame &val, RotationType type)
static bool IsRos()
void Update(Eigen::VectorXdRefConst x, Eigen::VectorXdRef phi) override
void(AvoidLookAtSphere::* UpdateTaskMapWithoutJacobian)(Eigen::VectorXdRefConst, Eigen::VectorXdRef)


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09