

Optimize calculations
@74bfef339dad5fc0807a5c09d96c517e26f2fd96
--- p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
+++ p9n_node/include/p9n_node/teleop_twist_joy_node.hpp
... | ... | @@ -32,7 +32,6 @@ |
32 | 32 |
using Joy = sensor_msgs::msg::Joy; |
33 | 33 |
|
34 | 34 |
private: |
35 |
- float speed_factor_ = 1.0; |
|
36 | 35 |
double linear_max_speed_, angular_max_speed_; |
37 | 36 |
|
38 | 37 |
p9n_interface::HW_TYPE hw_type_; |
--- p9n_node/src/teleop_twist_joy_node.cpp
+++ p9n_node/src/teleop_twist_joy_node.cpp
... | ... | @@ -64,15 +64,14 @@ |
64 | 64 |
this->timer_watchdog_->reset(); |
65 | 65 |
this->p9n_if_->setJoyMsg(joy_msg); |
66 | 66 |
|
67 |
- const double PI = 3.14159; |
|
68 | 67 |
static bool stopped = true; |
69 | 68 |
if (this->p9n_if_->isTiltedStickL()) { |
70 | 69 |
auto twist_msg = std::make_unique<Twist>(); |
71 | 70 |
twist_msg->linear.set__x(this->linear_max_speed_ * this->p9n_if_->tiltedStickLY()); |
72 | 71 |
|
73 |
- if (this->p9n_if_->tiltedStickLY() > sin(PI / 8)) { |
|
72 |
+ if (this->p9n_if_->tiltedStickLY() > sin(M_PI * 0.125)) { |
|
74 | 73 |
twist_msg->angular.set__z(this->angular_max_speed_ * this->p9n_if_->tiltedStickLX()); |
75 |
- } else if (this->p9n_if_->tiltedStickLY() < sin(-PI / 8)) { |
|
74 |
+ } else if (this->p9n_if_->tiltedStickLY() < sin(-M_PI * 0.125)) { |
|
76 | 75 |
twist_msg->angular.set__z(-this->angular_max_speed_ * this->p9n_if_->tiltedStickLX()); |
77 | 76 |
} else { |
78 | 77 |
twist_msg->linear.set__x(0.0); |
Add a comment
Delete comment
Once you delete this comment, you won't be able to recover it. Are you sure you want to delete this comment?