Skip to content

Commit bcaf5ab

Browse files
Update Eigen Vector sizes
1 parent 0bd94a6 commit bcaf5ab

File tree

1 file changed

+13
-13
lines changed

1 file changed

+13
-13
lines changed

kinematics_interface/test/kinematics_interface_common_tests.hpp

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -122,15 +122,15 @@ TYPED_TEST_P(TestPlugin, basic_plugin_function)
122122
ASSERT_TRUE(this->ik_->initialize(this->urdf_, this->node_->get_node_parameters_interface(), ""));
123123

124124
// calculate end effector transform
125-
Eigen::VectorXd pos = Eigen::Vector3d::Zero();
125+
auto pos = Eigen::VectorXd::Zero(3);
126126
Eigen::Isometry3d end_effector_transform;
127127
ASSERT_TRUE(
128128
this->ik_->calculate_link_transform(pos, this->end_effector_, end_effector_transform));
129129

130130
// convert cartesian delta to joint delta
131131
kinematics_interface::Vector6d delta_x = kinematics_interface::Vector6d::Zero();
132132
delta_x[2] = 1; // vz
133-
Eigen::VectorXd delta_theta = Eigen::Vector3d::Zero();
133+
Eigen::VectorXd delta_theta = Eigen::VectorXd::Zero(3);
134134
ASSERT_TRUE(this->ik_->convert_cartesian_deltas_to_joint_deltas(
135135
pos, delta_x, this->end_effector_, delta_theta));
136136

@@ -164,20 +164,20 @@ TYPED_TEST_P(TestPlugin, plugin_function_reduced_model_tip)
164164
ASSERT_TRUE(this->ik_->initialize(this->urdf_, this->node_->get_node_parameters_interface(), ""));
165165

166166
// calculate end effector transform
167-
Eigen::Matrix<double, Eigen::Dynamic, 1> pos = Eigen::Vector2d::Zero();
167+
auto pos = Eigen::VectorXd::Zero(2);
168168
Eigen::Isometry3d end_effector_transform;
169169
ASSERT_TRUE(
170170
this->ik_->calculate_link_transform(pos, this->end_effector_, end_effector_transform));
171171

172172
// convert cartesian delta to joint delta
173-
Eigen::Matrix<double, 6, 1> delta_x = Eigen::Matrix<double, 6, 1>::Zero();
173+
kinematics_interface::Vector6d delta_x = kinematics_interface::Vector6d::Zero();
174174
delta_x[2] = 1; // vz
175-
Eigen::Matrix<double, Eigen::Dynamic, 1> delta_theta = Eigen::Vector2d::Zero();
175+
Eigen::VectorXd delta_theta = Eigen::VectorXd::Zero(2);
176176
ASSERT_TRUE(this->ik_->convert_cartesian_deltas_to_joint_deltas(
177177
pos, delta_x, this->end_effector_, delta_theta));
178178

179179
// convert joint delta to cartesian delta
180-
Eigen::Matrix<double, 6, 1> delta_x_est;
180+
kinematics_interface::Vector6d delta_x_est;
181181
ASSERT_TRUE(this->ik_->convert_joint_deltas_to_cartesian_deltas(
182182
pos, delta_theta, this->end_effector_, delta_x_est));
183183

@@ -209,15 +209,15 @@ TYPED_TEST_P(TestPlugin, plugin_function_reduced_model_base)
209209
ASSERT_TRUE(this->ik_->initialize(this->urdf_, this->node_->get_node_parameters_interface(), ""));
210210

211211
// calculate end effector transform
212-
Eigen::VectorXd pos = Eigen::Vector2d::Zero();
212+
auto pos = Eigen::VectorXd::Zero(2);
213213
Eigen::Isometry3d end_effector_transform;
214214
ASSERT_TRUE(
215215
this->ik_->calculate_link_transform(pos, this->end_effector_, end_effector_transform));
216216

217217
// convert cartesian delta to joint delta
218218
kinematics_interface::Vector6d delta_x = kinematics_interface::Vector6d::Zero();
219219
delta_x[2] = 1; // vz
220-
Eigen::VectorXd delta_theta = Eigen::Vector2d::Zero();
220+
Eigen::VectorXd delta_theta = Eigen::VectorXd::Zero(2);
221221
ASSERT_TRUE(this->ik_->convert_cartesian_deltas_to_joint_deltas(
222222
pos, delta_x, this->end_effector_, delta_theta));
223223
// jacobian inverse for vz is singular in this configuration
@@ -325,17 +325,17 @@ TYPED_TEST_P(TestPlugin, incorrect_input_sizes)
325325
ASSERT_TRUE(this->ik_->initialize(this->urdf_, this->node_->get_node_parameters_interface(), ""));
326326

327327
// define correct values
328-
Eigen::Matrix<double, Eigen::Dynamic, 1> pos = Eigen::Vector2d::Zero();
328+
auto pos = Eigen::VectorXd::Zero(2);
329329
Eigen::Isometry3d end_effector_transform;
330-
Eigen::Matrix<double, 6, 1> delta_x = Eigen::Matrix<double, 6, 1>::Zero();
330+
kinematics_interface::Vector6d delta_x = kinematics_interface::Vector6d::Zero();
331331
delta_x[2] = 1;
332-
Eigen::Matrix<double, Eigen::Dynamic, 1> delta_theta = Eigen::Vector2d::Zero();
333-
Eigen::Matrix<double, 6, 1> delta_x_est;
332+
Eigen::VectorXd delta_theta = Eigen::VectorXd::Zero(2);
333+
kinematics_interface::Vector6d delta_x_est;
334334
Eigen::Matrix<double, Eigen::Dynamic, 6> jacobian = Eigen::Matrix<double, 2, 6>::Zero();
335335
Eigen::Matrix<double, 7, 1> x_a, x_b;
336336

337337
// wrong size input vector
338-
Eigen::Matrix<double, Eigen::Dynamic, 1> vec_5 = Eigen::Matrix<double, 5, 1>::Zero();
338+
Eigen::VectorXd vec_5 = Eigen::VectorXd::Zero(5);
339339

340340
// wrong size input jacobian
341341
Eigen::Matrix<double, Eigen::Dynamic, 6> mat_5_6 = Eigen::Matrix<double, 5, 6>::Zero();

0 commit comments

Comments
 (0)