Skip to content

Commit 17e9c79

Browse files
author
Tim Schneider
committed
Renamed LinearMotion -> CartesianMotion and LinearImpedanceMotion -> CartesianImpedanceMotion for consistency
1 parent 07beef3 commit 17e9c79

12 files changed

+54
-47
lines changed

README.md

+15-15
Original file line numberDiff line numberDiff line change
@@ -120,20 +120,20 @@ Robot robot("172.16.0.2");
120120
robot.setDynamicRel(0.05);
121121

122122
// Move the end-effector 20cm in positive x-direction
123-
auto motion = LinearMotion(RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);
123+
auto motion = CartesianMotion(RobotPose(Affine({0.2, 0.0, 0.0}), 0.0), ReferenceType::Relative);
124124

125125
// Finally move the robot
126126
robot.move(motion);
127127
```
128128
129129
The corresponding program in Python is
130130
```python
131-
from franky import Affine, LinearMotion, Robot, ReferenceType
131+
from franky import Affine, CartesianMotion, Robot, ReferenceType
132132
133133
robot = Robot("172.16.0.2")
134134
robot.relative_dynamics_factor = 0.05
135135
136-
motion = LinearMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
136+
motion = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
137137
robot.move(motion)
138138
```
139139

@@ -213,7 +213,7 @@ In python, you can use them as follows:
213213
```python
214214
import math
215215
from scipy.spatial.transform import Rotation
216-
from franky import JointWaypointMotion, JointWaypoint, JointPositionStopMotion, LinearMotion, CartesianWaypointMotion, CartesianWaypoint, Affine, RobotPose, ReferenceType, CartesianPoseStopMotion
216+
from franky import JointWaypointMotion, JointWaypoint, JointPositionStopMotion, CartesianMotion, CartesianWaypointMotion, CartesianWaypoint, Affine, RobotPose, ReferenceType, CartesianPoseStopMotion
217217

218218
# A point-to-point motion in the joint space
219219
m1 = JointWaypointMotion([JointWaypoint([-1.8, 1.1, 1.7, -2.1, -1.1, 1.6, -0.4])])
@@ -230,15 +230,15 @@ m3 = JointPositionStopMotion()
230230

231231
# A linear motion in cartesian space
232232
quat = Rotation.from_euler("xyz", [0, 0, math.pi / 2]).as_quat()
233-
m4 = LinearMotion(Affine([0.2, -0.4, 0.3], quat))
234-
m5 = LinearMotion(RobotPose(Affine([0.2, -0.4, 0.3], quat), elbow_position=1.7)) # With target elbow angle
233+
m4 = CartesianMotion(Affine([0.2, -0.4, 0.3], quat))
234+
m5 = CartesianMotion(RobotPose(Affine([0.2, -0.4, 0.3], quat), elbow_position=1.7)) # With target elbow angle
235235

236236
# A linear motion in cartesian space relative to the initial position
237237
# (Note that this motion is relative both in position and orientation. Hence, when the robot's end-effector is oriented
238238
# differently, it will move in a different direction)
239-
m6 = LinearMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
239+
m6 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
240240

241-
# Generalization of LinearMotion that allows for multiple waypoints
241+
# Generalization of CartesianMotion that allows for multiple waypoints
242242
m7 = CartesianWaypointMotion([
243243
CartesianWaypoint(RobotPose(Affine([0.2, -0.4, 0.3], quat), elbow_position=1.7)),
244244
# The following waypoint is relative to the prior one and 50% slower
@@ -266,11 +266,11 @@ By adding reactions to the motion data, the robot can react to unforeseen events
266266
In the Python API, you can define conditions by using a comparison between a robot's value and a given threshold.
267267
If the threshold is exceeded, the reaction fires.
268268
```python
269-
from franky import LinearMotion, Affine, ReferenceType, Measure, Reaction
269+
from franky import CartesianMotion, Affine, ReferenceType, Measure, Reaction
270270

271-
motion = LinearMotion(Affine([0.0, 0.0, 0.1]), ReferenceType.Relative) # Move down 10cm
271+
motion = CartesianMotion(Affine([0.0, 0.0, 0.1]), ReferenceType.Relative) # Move down 10cm
272272

273-
reaction_motion = LinearMotion(Affine([0.0, 0.0, 0.01]), ReferenceType.Relative) # Move up for 1cm
273+
reaction_motion = CartesianMotion(Affine([0.0, 0.0, 0.01]), ReferenceType.Relative) # Move up for 1cm
274274

275275
# Trigger reaction if the Z force is greater than 30N
276276
reaction = Reaction(Measure.FORCE_Z > 30.0, reaction_motion)
@@ -322,7 +322,7 @@ Hence, callbacks might be executed significantly after their respective reaction
322322

323323
In C++ you can additionally use lambdas to define more complex behaviours:
324324
```c++
325-
auto motion = LinearMotion(RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
325+
auto motion = CartesianMotion(RobotPose(Affine({0.0, 0.0, 0.2}), 0.0), ReferenceType::Relative);
326326

327327
// Stop motion if force is over 10N
328328
auto stop_motion = StopMotion<franka::CartesianPose>()
@@ -357,16 +357,16 @@ By setting the `asynchronous` parameter of `Robot.move` to `True`, the function
357357
Instead, it returns immediately and, thus, allows the main thread to set new motions asynchronously.
358358
```python
359359
import time
360-
from franky import Affine, LinearMotion, Robot, ReferenceType
360+
from franky import Affine, CartesianMotion, Robot, ReferenceType
361361
362362
robot = Robot("172.16.0.2")
363363
robot.relative_dynamics_factor = 0.05
364364
365-
motion1 = LinearMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
365+
motion1 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
366366
robot.move(motion1, asynchronous=True)
367367
368368
time.sleep(0.5)
369-
motion2 = LinearMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
369+
motion2 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
370370
robot.move(motion2, asynchronous=True)
371371
```
372372

examples/asynchronous.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
from argparse import ArgumentParser
22
import time
33

4-
from franky import Affine, LinearMotion, Robot, ReferenceType
4+
from franky import Affine, CartesianMotion, Robot, ReferenceType
55

66

77
if __name__ == "__main__":
@@ -13,11 +13,11 @@
1313
robot = Robot(args.host)
1414
robot.relative_dynamics_factor = 0.05
1515

16-
motion1 = LinearMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
16+
motion1 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
1717
robot.move(motion1, asynchronous=True)
1818

1919
time.sleep(0.5)
20-
motion2 = LinearMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
20+
motion2 = CartesianMotion(Affine([0.2, 0.0, 0.0]), ReferenceType.Relative)
2121
robot.move(motion2, asynchronous=True)
2222

2323
# Wait for the robot to finish its motion

examples/linear.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -21,11 +21,11 @@ int main(int argc, char *argv[]) {
2121

2222
// Define and move forwards
2323
auto way = mk_affine(0.0, 0.05, 0.0);
24-
auto motion_forward = std::make_shared<LinearMotion>(RobotPose(way), ReferenceType::Relative);
24+
auto motion_forward = std::make_shared<CartesianMotion>(RobotPose(way), ReferenceType::Relative);
2525
robot.move(motion_forward);
2626

2727
// And move backwards using the inverse motion
28-
auto motion_backward = std::make_shared<LinearMotion>(RobotPose(way.inverse()), ReferenceType::Relative);
28+
auto motion_backward = std::make_shared<CartesianMotion>(RobotPose(way.inverse()), ReferenceType::Relative);
2929
robot.move(motion_backward);
3030

3131
return 0;

examples/linear.py

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
from argparse import ArgumentParser
22

3-
from franky import Affine, LinearMotion, Robot, ReferenceType
3+
from franky import Affine, CartesianMotion, Robot, ReferenceType
44

55

66
if __name__ == "__main__":
@@ -18,9 +18,9 @@
1818

1919
# Define and move forwards
2020
target = Affine([0.0, 0.2, 0.0])
21-
motion_forward = LinearMotion(target, ReferenceType.Relative)
21+
motion_forward = CartesianMotion(target, ReferenceType.Relative)
2222
robot.move(motion_forward)
2323

2424
# And move backwards using the inverse motion
25-
motion_backward = LinearMotion(target.inverse)
25+
motion_backward = CartesianMotion(target.inverse)
2626
robot.move(motion_backward)

examples/reaction.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
from argparse import ArgumentParser
22

3-
from franky import Affine, JointMotion, Measure, Reaction, Robot, CartesianPoseStopMotion, LinearMotion, RobotPose, \
3+
from franky import Affine, JointMotion, Measure, Reaction, Robot, CartesianPoseStopMotion, CartesianMotion, RobotPose, \
44
RobotState, ReferenceType
55

66

@@ -27,7 +27,7 @@ def reaction_callback(robot_state: RobotState, rel_time: float, abs_time: float)
2727
# Define and move forwards
2828
reaction = Reaction(Measure.ForceZ < -5.0, CartesianPoseStopMotion())
2929
reaction.register_callback(reaction_callback)
30-
motion_down = LinearMotion(RobotPose(Affine([0.0, 0.0, -0.12]), -0.2), ReferenceType.Relative)
30+
motion_down = CartesianMotion(RobotPose(Affine([0.0, 0.0, -0.12]), -0.2), ReferenceType.Relative)
3131
motion_down.add_reaction(reaction)
3232

3333
# You can try to block the robot now.

franky/__init__.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -26,11 +26,12 @@
2626
CartesianPoseMotion,
2727
ImpedanceMotion,
2828
ExponentialImpedanceMotion,
29-
LinearImpedanceMotion,
29+
CartesianImpedanceMotion,
3030
JointWaypoint,
3131
JointWaypointMotion,
3232
JointMotion,
3333
CartesianWaypointMotion,
34+
CartesianMotion,
3435
LinearMotion,
3536
CartesianPoseStopMotion,
3637
JointPositionStopMotion,

include/franky.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,8 @@
66
#include "franky/motion/impedance_motion.hpp"
77
#include "franky/motion/joint_motion.hpp"
88
#include "franky/motion/joint_waypoint_motion.hpp"
9-
#include "franky/motion/linear_impedance_motion.hpp"
10-
#include "franky/motion/linear_motion.hpp"
9+
#include "franky/motion/cartesian_impedance_motion.hpp"
10+
#include "franky/motion/cartesian_motion.hpp"
1111
#include "franky/motion/measure.hpp"
1212
#include "franky/motion/motion.hpp"
1313
#include "franky/motion/motion_generator.hpp"

include/franky/motion/linear_impedance_motion.hpp include/franky/motion/cartesian_impedance_motion.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -10,16 +10,16 @@
1010

1111
namespace franky {
1212

13-
class LinearImpedanceMotion : public ImpedanceMotion {
13+
class CartesianImpedanceMotion : public ImpedanceMotion {
1414
public:
1515
struct Params : public ImpedanceMotion::Params {
1616
bool return_when_finished{true};
1717
double finish_wait_factor{1.2}; // Wait a bit longer to stop
1818
};
1919

20-
explicit LinearImpedanceMotion(const Affine &target, double duration);
20+
explicit CartesianImpedanceMotion(const Affine &target, double duration);
2121

22-
explicit LinearImpedanceMotion(const Affine &target, double duration, const Params &params);
22+
explicit CartesianImpedanceMotion(const Affine &target, double duration, const Params &params);
2323

2424
protected:
2525
void initImpl(const franka::RobotState &robot_state, const std::optional<franka::Torques> &previous_command) override;

include/franky/motion/linear_motion.hpp include/franky/motion/cartesian_motion.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -10,14 +10,17 @@
1010

1111
namespace franky {
1212

13-
class LinearMotion : public CartesianWaypointMotion {
13+
class CartesianMotion : public CartesianWaypointMotion {
1414
public:
15-
explicit LinearMotion(
15+
explicit CartesianMotion(
1616
const RobotPose &target,
1717
ReferenceType reference_type = ReferenceType::Absolute,
1818
const Affine &frame = Affine::Identity(),
1919
RelativeDynamicsFactor relative_dynamics_factor = 1.0,
2020
bool return_when_finished = true);
2121
};
2222

23+
// Backwards compatibility
24+
using LinearMotion = CartesianMotion;
25+
2326
} // namespace franky

python/python.cpp

+8-5
Original file line numberDiff line numberDiff line change
@@ -586,7 +586,7 @@ PYBIND11_MODULE(_franky, m) {
586586
"force_constraints"_a = std::nullopt,
587587
"exponential_decay"_a = 0.005);
588588

589-
py::class_<LinearImpedanceMotion, ImpedanceMotion, std::shared_ptr<LinearImpedanceMotion>>(m, "LinearImpedanceMotion")
589+
py::class_<CartesianImpedanceMotion, ImpedanceMotion, std::shared_ptr<CartesianImpedanceMotion>>(m, "CartesianImpedanceMotion")
590590
.def(py::init<>([](
591591
const Affine &target,
592592
double duration,
@@ -604,9 +604,9 @@ PYBIND11_MODULE(_franky, m) {
604604
force_constraints_active[i] = force_constraints.value()[i].has_value();
605605
}
606606
}
607-
return std::make_shared<LinearImpedanceMotion>(
607+
return std::make_shared<CartesianImpedanceMotion>(
608608
target, duration,
609-
LinearImpedanceMotion::Params{
609+
CartesianImpedanceMotion::Params{
610610
target_type, translational_stiffness, rotational_stiffness, force_constraints_value,
611611
force_constraints_active, return_when_finished, finish_wait_factor});
612612
}),
@@ -698,14 +698,14 @@ PYBIND11_MODULE(_franky, m) {
698698
"relative_dynamics_factor"_a = 1.0,
699699
"return_when_finished"_a = true);
700700

701-
py::class_<LinearMotion, CartesianWaypointMotion, std::shared_ptr<LinearMotion>>(m, "LinearMotion")
701+
py::class_<CartesianMotion, CartesianWaypointMotion, std::shared_ptr<CartesianMotion>>(m, "CartesianMotion")
702702
.def(py::init<>([](
703703
const RobotPose &target,
704704
ReferenceType reference_type,
705705
const std::optional<Affine> &frame,
706706
RelativeDynamicsFactor relative_dynamics_factor,
707707
bool return_when_finished) {
708-
return std::make_shared<LinearMotion>(
708+
return std::make_shared<CartesianMotion>(
709709
target,
710710
reference_type,
711711
frame.value_or(Affine::Identity()),
@@ -718,6 +718,9 @@ PYBIND11_MODULE(_franky, m) {
718718
"relative_dynamics_factor"_a = 1.0,
719719
"return_when_finished"_a = true);
720720

721+
// Backwards compatibility
722+
m.attr("LinearMotion") = m.attr("CartesianMotion");
723+
721724
py::class_<StopMotion<franka::CartesianPose>,
722725
Motion<franka::CartesianPose>,
723726
std::shared_ptr<StopMotion<franka::CartesianPose>>>(m, "CartesianPoseStopMotion")

src/motion/linear_impedance_motion.cpp src/motion/cartesian_impedance_motion.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "franky/motion/linear_impedance_motion.hpp"
1+
#include "franky/motion/cartesian_impedance_motion.hpp"
22

33
#include <map>
44

@@ -9,22 +9,22 @@
99

1010
namespace franky {
1111

12-
LinearImpedanceMotion::LinearImpedanceMotion(const Affine &target, double duration)
13-
: LinearImpedanceMotion(target, duration, Params()) {}
12+
CartesianImpedanceMotion::CartesianImpedanceMotion(const Affine &target, double duration)
13+
: CartesianImpedanceMotion(target, duration, Params()) {}
1414

15-
LinearImpedanceMotion::LinearImpedanceMotion(
16-
const Affine &target, double duration, const LinearImpedanceMotion::Params &params)
15+
CartesianImpedanceMotion::CartesianImpedanceMotion(
16+
const Affine &target, double duration, const CartesianImpedanceMotion::Params &params)
1717
: duration_(duration), params_(params), ImpedanceMotion(target, params) {}
1818

19-
void LinearImpedanceMotion::initImpl(
19+
void CartesianImpedanceMotion::initImpl(
2020
const franka::RobotState &robot_state,
2121
const std::optional<franka::Torques> &previous_command) {
2222
ImpedanceMotion::initImpl(robot_state, previous_command);
2323
initial_pose_ = Affine(Eigen::Matrix4d::Map(robot_state.O_T_EE_c.data()));
2424
}
2525

2626
std::tuple<Affine, bool>
27-
LinearImpedanceMotion::update(const franka::RobotState &robot_state, franka::Duration time_step, double time) {
27+
CartesianImpedanceMotion::update(const franka::RobotState &robot_state, franka::Duration time_step, double time) {
2828
double transition_parameter = time / duration_;
2929
Affine intermediate_goal;
3030
bool done;

src/motion/linear_motion.cpp src/motion/cartesian_motion.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
1-
#include "franky/motion/linear_motion.hpp"
1+
#include "franky/motion/cartesian_motion.hpp"
22

33
#include "franky/robot_pose.hpp"
44
#include "franky/motion/cartesian_waypoint_motion.hpp"
55

66
namespace franky {
77

8-
LinearMotion::LinearMotion(
8+
CartesianMotion::CartesianMotion(
99
const RobotPose &target,
1010
ReferenceType reference_type,
1111
const Affine& frame,

0 commit comments

Comments
 (0)