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

widget_speed y is not subscribing rotational speed #7

Closed
tonaaskarwur opened this issue Aug 17, 2020 · 4 comments
Closed

widget_speed y is not subscribing rotational speed #7

tonaaskarwur opened this issue Aug 17, 2020 · 4 comments

Comments

@tonaaskarwur
Copy link

I'm trying to learn to make GUI with qt qreator (ros industrial) using your code.
I found some errors in the y speed widget which should have been corresponding to rotational speed.
It is not responding.
I tried to edit the callback function from qnode.cpp, but I could't make it work.
Do you have any ideas?
Thank you

@chengyangkj
Copy link
Owner

I'm trying to learn to make GUI with qt qreator (ros industrial) using your code.
I found some errors in the y speed widget which should have been corresponding to rotational speed.
It is not responding.
I tried to edit the callback function from qnode.cpp, but I could't make it work.
Do you have any ideas?
Thank you

To be precise, I'm not subscribing here to the rotational speed, it's just the y-axis speed. In the 143-line speedCallback() function of qnode.cpp,:

void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg) { emit speed_x(msg->twist.twist.linear.x); emit speed_y(msg->twist.twist.linear.y); }

send a custom signal to mainwindow.cpp, you can change the y-axis speed here to the raw value to send past, in mainWindow.cpp's slot_speed_x (double x) and slot_speed_y (double x) functions handle the signal sent over and update the UI display.

@tonaaskarwur
Copy link
Author

Thank you for the advice.
I did as you advised like this:
(qnode.cpp)
//Speed callback function
void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
{
emit speed_x(msg->twist.twist.linear.x);
emit speed_y(msg->twist.twist.linear.y);
}

(mainwindow.cpp)
void MainWindow::connections()
{
//connectSpeed signal
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_x(double)));
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_y(double)));

Now both widget are subscribing to the same speed variable in my display.
Sorry but I don't understand how to change the y-axis speed to the raw value.
I wanted the widget_speed_x to subscribe forward/backward speed and widget_speed_y to subscribe left/right speed.
Thank you so much for your help, really.

@chengyangkj
Copy link
Owner

//connectSpeed signal
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_x(double)));
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_y(double)));

//connectSpeed signal
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_x(double)));
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_y(double)));
All of you are linking here are speed_x (double) signals, so it will cause the y-axis speed to be the same as the x-axis.

The original code is:
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_x(double))); connect(&qnode,SIGNAL(speed_y(double)),this,SLOT(slot_speed_y(double)));

Only change this:
void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg) { emit speed_x(msg->twist.twist.linear.x); emit speed_y(msg->twist.twist.linear.y); }

as:

void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg) { emit speed_x(msg->twist.twist.linear.x); emit speed_y(msg->twist.twist.angular.z); }

The z-axis angle speed was released to mainwindow.cpp ,slot_speed_y(double):
So you need to change the ui display in the slot_speed_y function:

void MainWindow::slot_speed_y(double x) { if(x>=0) ui.label_dir_y->setText("正向"); else ui.label_dir_y->setText("反向"); m_DashBoard_y->setValue(abs(x*100)); }

@tonaaskarwur
Copy link
Author

Thank you for your kind response..
so I changed as you mentioned.
in mainwindow.cpp =
...
//connectSpeed signal
connect(&qnode,SIGNAL(speed_x(double)),this,SLOT(slot_speed_x(double)));
connect(&qnode,SIGNAL(speed_y(double)),this,SLOT(slot_speed_y(double)));
...
void MainWindow::slot_speed_x(double x)
{
if(x>=0) ui.label_dir_x->setText("正向");
else ui.label_dir_x->setText("反向");

m_DashBoard_x->setValue(abs(x*100));

}
void MainWindow::slot_speed_y(double z)
{
if(z>=0) ui.label_dir_y->setText("正向");
else ui.label_dir_y->setText("反向");

m_DashBoard_y->setValue((z*100));

}
..

and qnode.cpp =
...
//Speed callback function
void QNode::speedCallback(const nav_msgs::Odometry::ConstPtr& msg)
{
emit speed_x(msg->twist.twist.linear.x);
emit speed_y(msg->twist.twist.angular.z);
}
...

When I run this, the y_speed_widget is responding, but it doesn't respond to the angular speed.

Screencast from 2020年08月17日 14時52分00秒

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants