Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed Issue #15: rxros::spin() function uses unnecessary many threads. #11

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions brickpi3/src/BrickPi3BaseController_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ enum WheelId{ LEFT_WHEEL = 0, RIGHT_WHEEL = 1};

int main(int argc, char** argv)
{
rxros::init(argc, argv, "brickpi3_base_controller"); // Name of this node.
ros::init(argc, argv, "brickpi3_base_controller"); // Name of this node.

const auto l_wheel_joint = rxros::parameter::get("/brickpi3/l_wheel_joint", "l_wheel_joint");
const auto r_wheel_joint = rxros::parameter::get("/brickpi3/r_wheel_joint", "r_wheel_joint");
Expand Down Expand Up @@ -104,5 +104,5 @@ int main(int argc, char** argv)
| map(effort_2_joint_cmd(RIGHT_WHEEL))
| publish_to_topic<brickpi3_msgs::JointCommand>("/joint_command");

rxros::spin();
ros::spin();
}
4 changes: 2 additions & 2 deletions brickpi3/src/BrickPi3JointStatesPublisher_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ auto tuple_2_joint_states = [](const auto& ljs, const auto& rjs) { // tuple: lef

int main(int argc, char** argv)
{
rxros::init(argc, argv, "brickpi3_joint_states_publisher"); // Name of this node.
ros::init(argc, argv, "brickpi3_joint_states_publisher"); // Name of this node.

const auto l_wheel_joint = rxros::parameter::get("/brickpi3/l_wheel_joint", "l_wheel_joint");
const auto r_wheel_joint = rxros::parameter::get("/brickpi3/r_wheel_joint", "r_wheel_joint");
Expand All @@ -68,5 +68,5 @@ int main(int argc, char** argv)
left_wheel_observable.zip(tuple_2_joint_states, right_wheel_observable)
| publish_to_topic<sensor_msgs::JointState>("/joint_states");

rxros::spin();
ros::spin();
}
8 changes: 4 additions & 4 deletions brickpi3/src/BrickPi3Observable_rx.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ namespace brickpi3
brickPi3.set_sensor_type(id, SENSOR_TYPE_TOUCH_NXT);

ros::Rate rate(frequency);
while (rxros::ok()) {
while (ros::ok()) {
sensor_touch_t touch;
int rc = brickPi3.get_sensor(id, &touch);
if (rc == 0) {
Expand Down Expand Up @@ -98,7 +98,7 @@ namespace brickpi3
brickPi3.set_sensor_type(id, SENSOR_TYPE_NXT_COLOR_FULL);

ros::Rate rate(frequency);
while (rxros::ok()) {
while (ros::ok()) {
sensor_color_t color;
int rc = brickPi3.get_sensor(id, &color);
if (rc == 0) {
Expand Down Expand Up @@ -130,7 +130,7 @@ namespace brickpi3
brickPi3.set_sensor_type(id, SENSOR_TYPE_NXT_ULTRASONIC);

ros::Rate rate(frequency);
while (rxros::ok()) {
while (ros::ok()) {
sensor_ultrasonic_t ultrasonic;
int rc = brickPi3.get_sensor(id, &ultrasonic);
if (rc == 0) {
Expand Down Expand Up @@ -162,7 +162,7 @@ namespace brickpi3
brickPi3.reset_motor_encoder(id);

ros::Rate rate(frequency);
while (rxros::ok()) {
while (ros::ok()) {
actuator_motor_t motor{};
int rc = brickPi3.get_motor_status(id, motor.motorState, motor.motorPower, motor.motorPosition, motor.motorDPS);
if (rc == 0) {
Expand Down
4 changes: 2 additions & 2 deletions brickpi3/src/BrickPi3OdomPublisher_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ using namespace rxros::operators;

int main(int argc, char** argv)
{
rxros::init(argc, argv, "brickpi3_odom_publisher"); // Name of this node.
ros::init(argc, argv, "brickpi3_odom_publisher"); // Name of this node.

const auto l_wheel_joint = rxros::parameter::get("/brickpi3/l_wheel_joint", "l_wheel_joint");
const auto r_wheel_joint = rxros::parameter::get("/brickpi3/r_wheel_joint", "r_wheel_joint");
Expand Down Expand Up @@ -107,5 +107,5 @@ int main(int argc, char** argv)
| map(stsTuple2Odometry)
| publish_to_topic<nav_msgs::Odometry>("/odom");

rxros::spin();
ros::spin();
}
4 changes: 2 additions & 2 deletions brickpi3/src/BrickPi3Ros_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ auto join_with_latest_from(const Observable& observable) {


int main(int argc, char** argv) {
rxros::init(argc, argv, "brickpi3"); // Name of this node.
ros::init(argc, argv, "brickpi3"); // Name of this node.

auto touchEvent2ContactMsg = [] (const std::string& frameId) {
return [=](const sensor_touch_t& touchEvent) {
Expand Down Expand Up @@ -154,5 +154,5 @@ int main(int argc, char** argv) {
}},
[](){}); // on completed event

rxros::spin();
ros::spin();
}
4 changes: 2 additions & 2 deletions rxros_listener/src/rxros_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,14 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

int main(int argc, char **argv)
{
rxros::init(argc, argv, "listener");
ros::init(argc, argv, "listener");

rxros::observable::from_topic<std_msgs::String>("/chatter", 1000)
.subscribe ( [] (const std_msgs::String& msg) {
ROS_INFO_STREAM ("I heard: [" << msg.data << "]");
});

rxros::spin();
ros::spin();

return 0;
}
4 changes: 2 additions & 2 deletions rxros_talker/src/rxros_talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int main(int argc, char **argv)
{
using namespace rxcpp::operators;

rxros::init(argc, argv, "talker");
ros::init(argc, argv, "talker");
const std::string hello = "hello world ";

rxcpp::observable<>::interval (std::chrono::milliseconds (1000))
Expand All @@ -58,6 +58,6 @@ int main(int argc, char **argv)
{ ROS_INFO_STREAM (msg.data); })
| rxros::operators::publish_to_topic<std_msgs::String> ("/chatter", 1000);

rxros::spin();
ros::spin();
return 0;
}
4 changes: 2 additions & 2 deletions rxros_teleop/src/JoystickPublisher_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ struct joystick_event

int main(int argc, char** argv)
{
rxros::init(argc, argv, "joystick_publisher"); // Name of this Node.
ros::init(argc, argv, "joystick_publisher"); // Name of this Node.

const auto joystickDevice = rxros::parameter::get("/joystick_publisher/device", "/dev/input/js0");
rxros::logging().info() << "Joystick device: " << joystickDevice;
Expand Down Expand Up @@ -95,5 +95,5 @@ int main(int argc, char** argv)
| publish_to_topic<rxros_teleop_msgs::Joystick>("/joystick");

rxros::logging().info() << "Spinning joystick_publisher ...";
rxros::spin();
ros::spin();
}
4 changes: 2 additions & 2 deletions rxros_teleop/src/KeyboardPublisher_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ using namespace rxros::operators;

int main(int argc, char** argv)
{
rxros::init(argc, argv, "keyboard_publisher"); // Name of this Node.
ros::init(argc, argv, "keyboard_publisher"); // Name of this Node.

const auto keyboardDevice = rxros::parameter::get("/keyboard_publisher/device", "/dev/input/event4"); // Use event4 for dell, event4 for nuc and event1 for others
rxros::logging().info() << "Keyboard device: " << keyboardDevice;
Expand Down Expand Up @@ -67,5 +67,5 @@ int main(int argc, char** argv)
| publish_to_topic<rxros_teleop_msgs::Keyboard>("/keyboard");

rxros::logging().info() << "Spinning keyboard_publisher...";
rxros::spin();
ros::spin();
}
4 changes: 2 additions & 2 deletions rxros_teleop/src/VelocityPublisher_rx.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ using namespace rxros::operators;


int main(int argc, char** argv) {
rxros::init(argc, argv, "velocity_publisher"); // Name of this node.
ros::init(argc, argv, "velocity_publisher"); // Name of this node.

const auto frequencyInHz = rxros::parameter::get("/velocity_publisher/frequency", 10.0); // hz
const auto minVelLinear = rxros::parameter::get("/velocity_publisher/min_vel_linear", 0.04); // m/s
Expand Down Expand Up @@ -98,5 +98,5 @@ int main(int argc, char** argv) {
| publish_to_topic<geometry_msgs::Twist>("/cmd_vel"); // publish the Twist messages to the topic "/cmd_vel"

rxros::logging().info() << "Spinning velocity_publisher ...";
rxros::spin();
ros::spin();
}