Skip to content

Commit ff00661

Browse files
committed
Update to upstream changes
1 parent d195e04 commit ff00661

File tree

5 files changed

+32
-29
lines changed

5 files changed

+32
-29
lines changed

tesseract_python/swig/tesseract_common_python.i

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#include <tesseract_common/status_code.h>
4242
#include <tesseract_common/resource.h>
4343
#include <tesseract_common/manipulator_info.h>
44+
#include <tesseract_common/joint_state.h>
4445

4546
%}
4647

@@ -133,6 +134,7 @@ namespace tesseract_common
133134
%include "tesseract_common/status_code.h"
134135
%include "tesseract_common/resource.h"
135136
%include "tesseract_common/manipulator_info.h"
137+
%include "tesseract_common/joint_state.h"
136138

137139

138140

tesseract_python/swig/tesseract_environment_python.i

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,28 @@
6767
#define TESSERACT_ENVIRONMENT_CORE_PUBLIC
6868
%include "tesseract_environment/core/types.h"
6969
%include "tesseract_environment/core/commands.h"
70+
%include "tesseract_environment/core/command.h"
71+
%include "tesseract_environment/core/commands/add_allowed_collision_command.h"
72+
%include "tesseract_environment/core/commands/add_link_command.h"
73+
%include "tesseract_environment/core/commands/add_kinematics_information_command.h"
74+
%include "tesseract_environment/core/commands/add_scene_graph_command.h"
75+
%include "tesseract_environment/core/commands/change_default_contact_margin_command.h"
76+
%include "tesseract_environment/core/commands/change_joint_acceleration_limits_command.h"
77+
%include "tesseract_environment/core/commands/change_joint_origin_command.h"
78+
%include "tesseract_environment/core/commands/change_joint_position_limits_command.h"
79+
%include "tesseract_environment/core/commands/change_joint_velocity_limits_command.h"
80+
%include "tesseract_environment/core/commands/change_link_collision_enabled_command.h"
81+
%include "tesseract_environment/core/commands/change_link_origin_command.h"
82+
%include "tesseract_environment/core/commands/change_link_visibility_command.h"
83+
%include "tesseract_environment/core/commands/change_pair_contact_margin_command.h"
84+
%include "tesseract_environment/core/commands/move_joint_command.h"
85+
%include "tesseract_environment/core/commands/move_link_command.h"
86+
%include "tesseract_environment/core/commands/remove_allowed_collision_command.h"
87+
%include "tesseract_environment/core/commands/remove_allowed_collision_link_command.h"
88+
%include "tesseract_environment/core/commands/remove_joint_command.h"
89+
%include "tesseract_environment/core/commands/remove_link_command.h"
90+
%include "tesseract_environment/core/commands/replace_joint_command.h"
91+
7092
%include "tesseract_environment/core/manipulator_manager.h"
7193
%include "tesseract_environment/core/state_solver.h"
7294
%include "tesseract_environment/core/environment.h"

tesseract_python/swig/tesseract_kinematics_python.i

Lines changed: 0 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -58,26 +58,6 @@
5858

5959
%template(pair_bool_matrix) std::pair<bool,Eigen::MatrixXd>;
6060

61-
%extend tesseract_kinematics::ForwardKinematics {
62-
63-
bool calcJacobian(Eigen::MatrixXd& jacobian, const Eigen::Ref<const Eigen::VectorXd>& joint_angles) const
64-
{
65-
jacobian = Eigen::MatrixXd(6, joint_angles.rows());
66-
bool res = $self->calcJacobian(jacobian, joint_angles);
67-
68-
return res;
69-
}
70-
71-
bool calcJacobian(Eigen::MatrixXd& jacobian, const Eigen::Ref<const Eigen::VectorXd>& joint_angles, const std::string& link_name) const
72-
{
73-
jacobian = Eigen::MatrixXd(6, joint_angles.rows());
74-
bool res = $self->calcJacobian(jacobian, joint_angles, link_name);
75-
return res;
76-
}
77-
}
78-
79-
%ignore calcJacobian;
80-
8161
// tesseract_kinematics
8262
#define TESSERACT_KINEMATICS_CORE_PUBLIC
8363
#define TESSERACT_KINEMATICS_IKFAST_PUBLIC

tesseract_python/tests/tesseract_kinematics/test_kdl_kinematics.py

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -83,12 +83,11 @@ def run_inv_kin_test(inv_kin, fwd_kin):
8383
pose[2,3] = 1.306
8484

8585
seed = np.array([-0.785398, 0.785398, -0.785398, 0.785398, -0.785398, 0.785398, -0.785398])
86-
res, solutions = inv_kin.calcInvKin(tesseract_common.Isometry3d(pose),seed)
87-
assert res
88-
89-
res, result = fwd_kin.calcFwdKin(solutions)
90-
assert res
86+
solutions = inv_kin.calcInvKin(tesseract_common.Isometry3d(pose),seed)
87+
assert len(solutions) > 0
9188

89+
result = fwd_kin.calcFwdKin(solutions[0])
90+
9291
nptest.assert_almost_equal(pose,result.matrix(),decimal=3)
9392

9493
def test_kdl_kin_chain_lma_inverse_kinematic():
@@ -117,7 +116,7 @@ def test_jacobian():
117116
jvals = np.array([-0.785398, 0.785398, -0.785398, 0.785398, -0.785398, 0.785398, -0.785398])
118117

119118
link_name = "tool0"
120-
res, jacobian = kin.calcJacobian(jvals,link_name)
121-
assert res
119+
jacobian = kin.calcJacobian(jvals,link_name)
120+
122121
assert jacobian.shape == (6,7)
123122

tesseract_python/tests/tesseract_motion_planning/test_simple_planner.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ def test_interpolatestatewaypoint_jointcart_freespace():
4949
request.env_state = env.getCurrentState()
5050
fwd_kin = env.getManipulatorManager().getFwdKinematicSolver(manip_info.manipulator)
5151
wp1 = JointWaypoint(joint_names, np.zeros((7,),dtype=np.float64))
52-
wp2 = CartesianWaypoint(fwd_kin.calcFwdKin(np.ones((7,),dtype=np.float64))[1])
52+
wp2 = CartesianWaypoint(fwd_kin.calcFwdKin(np.ones((7,),dtype=np.float64)))
5353
instr1 = PlanInstruction(Waypoint(wp1), PlanInstructionType_START, "TEST_PROFILE", manip_info)
5454
instr2 = PlanInstruction(Waypoint(wp2), PlanInstructionType_FREESPACE, "TEST_PROFILE", manip_info)
5555

@@ -63,5 +63,5 @@ def test_interpolatestatewaypoint_jointcart_freespace():
6363

6464
mi = composite[-1].cast_const_MoveInstruction()
6565
last_position = mi.getWaypoint().cast_const_StateWaypoint().position
66-
_, final_pose = fwd_kin.calcFwdKin(last_position)
66+
final_pose = fwd_kin.calcFwdKin(last_position)
6767
assert wp2.isApprox(final_pose, 1e-3)

0 commit comments

Comments
 (0)