Skip to content

Commit 120de0f

Browse files
Renamed values of ReferenceType enum to follow google style guide
1 parent a971b49 commit 120de0f

14 files changed

+22
-22
lines changed

examples/linear.cpp

Lines changed: 2 additions & 2 deletions
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<CartesianMotion>(RobotPose(way), ReferenceType::Relative);
24+
auto motion_forward = std::make_shared<CartesianMotion>(RobotPose(way), ReferenceType::kRelative);
2525
robot.move(motion_forward);
2626

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

3131
return 0;

include/franky/motion/cartesian_motion.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ class CartesianMotion : public CartesianWaypointMotion {
2424
*/
2525
explicit CartesianMotion(
2626
const CartesianState &target,
27-
ReferenceType reference_type = ReferenceType::Absolute,
27+
ReferenceType reference_type = ReferenceType::kAbsolute,
2828
const RelativeDynamicsFactor &relative_dynamics_factor = 1.0,
2929
bool return_when_finished = true,
3030
const Affine &frame = Affine::Identity());

include/franky/motion/impedance_motion.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ class ImpedanceMotion : public Motion<franka::Torques> {
2626
*/
2727
struct Params {
2828
/** The type of the target reference (relative or absolute). */
29-
ReferenceType target_type{ReferenceType::Absolute};
29+
ReferenceType target_type{ReferenceType::kAbsolute};
3030

3131
/** The translational stiffness in [10, 3000] N/m. */
3232
double translational_stiffness{2000};

include/franky/motion/joint_motion.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ class JointMotion : public JointWaypointMotion {
2121
*/
2222
explicit JointMotion(
2323
const JointState &target,
24-
ReferenceType reference_type = ReferenceType::Absolute,
24+
ReferenceType reference_type = ReferenceType::kAbsolute,
2525
const RelativeDynamicsFactor &relative_dynamics_factor = 1.0,
2626
bool return_when_finished = true);
2727
};

include/franky/motion/position_waypoint_motion.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ namespace franky {
1818
*/
1919
template<typename TargetType>
2020
struct PositionWaypoint : public Waypoint<TargetType> {
21-
ReferenceType reference_type{ReferenceType::Absolute};
21+
ReferenceType reference_type{ReferenceType::kAbsolute};
2222
};
2323

2424
/**

include/franky/motion/reference_type.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@ namespace franky {
88
* This enum class defines the reference types for motions (absolute or relative).
99
*/
1010
enum class ReferenceType {
11-
Absolute,
12-
Relative
11+
kAbsolute,
12+
kRelative
1313
};
1414

1515
} // namespace franky

include/franky/motion/stop_motion.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ class StopMotion<franka::JointPositions> : public JointMotion {
1919
public:
2020
explicit StopMotion() : JointMotion(
2121
JointState(Vector7d::Zero()),
22-
ReferenceType::Relative,
22+
ReferenceType::kRelative,
2323
RelativeDynamicsFactor::MAX_DYNAMICS()
2424
) {}
2525
};
@@ -45,7 +45,7 @@ class StopMotion<franka::CartesianPose> : public CartesianMotion {
4545
public:
4646
explicit StopMotion() : CartesianMotion(
4747
RobotPose(Affine::Identity()),
48-
ReferenceType::Relative,
48+
ReferenceType::kRelative,
4949
RelativeDynamicsFactor::MAX_DYNAMICS()
5050
) {}
5151
};

python/bind_enums.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@ using namespace franky;
88

99
void bind_enums(py::module &m) {
1010
py::enum_<ReferenceType>(m, "ReferenceType")
11-
.value("Relative", ReferenceType::Relative)
12-
.value("Absolute", ReferenceType::Absolute);
11+
.value("Relative", ReferenceType::kRelative)
12+
.value("Absolute", ReferenceType::kAbsolute);
1313

1414
py::enum_<franka::ControllerMode>(m, "ControllerMode")
1515
.value("JointImpedance", franka::ControllerMode::kJointImpedance)

python/bind_motion_cartesian_pos.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ void bind_motion_cartesian_pos(py::module &m) {
2323
}
2424
),
2525
"target"_a,
26-
py::arg_v("reference_type", ReferenceType::Absolute, "_franky.ReferenceType.Absolute"),
26+
py::arg_v("reference_type", ReferenceType::kAbsolute, "_franky.ReferenceType.Absolute"),
2727
"relative_dynamics_factor"_a = 1.0,
2828
"minimum_time"_a = std::nullopt,
2929
"hold_target_duration"_a = franka::Duration(0))
@@ -63,7 +63,7 @@ void bind_motion_cartesian_pos(py::module &m) {
6363
ee_frame.value_or(Affine::Identity()));
6464
}),
6565
"target"_a,
66-
py::arg_v("reference_type", ReferenceType::Absolute, "_franky.ReferenceType.Absolute"),
66+
py::arg_v("reference_type", ReferenceType::kAbsolute, "_franky.ReferenceType.Absolute"),
6767
"relative_dynamics_factor"_a = 1.0,
6868
"return_when_finished"_a = true,
6969
"ee_frame"_a = std::nullopt);

python/bind_motion_joint_pos.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ void bind_motion_joint_pos(py::module &m) {
2424
}
2525
),
2626
"target"_a,
27-
py::arg_v("reference_type", ReferenceType::Absolute, "_franky.ReferenceType.Absolute"),
27+
py::arg_v("reference_type", ReferenceType::kAbsolute, "_franky.ReferenceType.Absolute"),
2828
"relative_dynamics_factor"_a = 1.0,
2929
"minimum_time"_a = std::nullopt,
3030
"hold_target_duration"_a = franka::Duration(0))
@@ -50,7 +50,7 @@ void bind_motion_joint_pos(py::module &m) {
5050
py::class_<JointMotion, JointWaypointMotion, std::shared_ptr<JointMotion>>(m, "JointMotion")
5151
.def(py::init<const JointState &, ReferenceType, double, bool>(),
5252
"target"_a,
53-
py::arg_v("reference_type", ReferenceType::Absolute, "_franky.ReferenceType.Absolute"),
53+
py::arg_v("reference_type", ReferenceType::kAbsolute, "_franky.ReferenceType.Absolute"),
5454
"relative_dynamics_factor"_a = 1.0,
5555
"return_when_finished"_a = true);
5656

0 commit comments

Comments
 (0)