-
Notifications
You must be signed in to change notification settings - Fork 29
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
How to send waypoint to my flight card ? #49
Comments
I have not tested the You can increase the logger level to debug to get more informative output. Looking at the source code, receiving this error indicates that Your EOF message may further indicate a connection error. A request with an unsupported MSP ID should not cause connection issues. Have you encountered other connection issues over your serial connection? Can you:
|
This message has a bug. Fixed code: // MSP_SET_WP: 209
struct SetWp : public Message {
SetWp(FirmwareVariant v) : Message(v) {}
virtual ID id() const override { return ID::MSP_SET_WP; }
Value<uint8_t> number;
Value<uint8_t> action;
Value<int32_t> lat;
Value<int32_t> lon;
Value<int32_t> alt;
Value<int16_t> p1;
Value<int16_t> p2;
Value<int16_t> p3;
Value<uint8_t> nav_flag;
virtual ByteVectorUptr encode() const override {
ByteVectorUptr data = std::make_unique<ByteVector>();
bool rc = true;
rc &= data->pack(number);
rc &= data->pack(action);
rc &= data->pack(lat);
rc &= data->pack(lon);
rc &= data->pack(alt);
rc &= data->pack(p1);
rc &= data->pack(p2);
if(fw_variant == FirmwareVariant::INAV) {
rc &= data->pack(p3);
}
rc &= data->pack(nav_flag);
return data;
}
}; |
Also I find a bug in sendMessage at decoding empty payload data. decode_success = message.decode(data); Change to: decode_success = data.size() == 0 || message.decode(data); SET_WP has empty payload data in answer. I fixed in this library and some other things, maybe will made pull request. |
The original @DC-SWAT Is there an official document with the iNav message definitions? Could you provide a PR that adapts the iNav specific definition? I am not using iNav, so I cannot test the new definition myself. At the moment, we only differentiate between different firmware types, not versions. For simplicity, we could always update message definitions to the newest version of that firmware and thus completely neglecting backward compatibility to earlier firmware versions. Otherwise, you have to provide your own definition of
Thanks for the hint. Is this causing the EOF error? I am using |
#include <FlightController.hpp>
#include
#include <msp_msg.hpp>
#define MSP_NAV_STATUS_WAYPOINT_ACTION_WAYPOINT 0x01
struct SetWp : public Message {
SetWp(FirmwareVariant v) : Message(v) {}
virtual ID id() const override { return ID::MSP_SET_WP; }
Value<uint8_t> wp_no;
Value<uint8_t> action;
Value<uint32_t> lat;
Value<uint32_t> lon;
Value<uint32_t> alt;
Value<uint16_t> p1;
Value<uint16_t> p2;
Value<uint16_t> p3;
Value<uint8_t> nav_flag;
virtual ByteVectorUptr encode() const override {
ByteVectorUptr data = std::make_unique<ByteVector>();
bool rc = true;
rc &= data->pack(wp_no);
rc &= data->pack(action);
rc &= data->pack(lat);
rc &= data->pack(lon);
rc &= data->pack(alt);
rc &= data->pack(p1);
rc &= data->pack(p2);
if(fw_variant == FirmwareVariant::INAV) {
rc &= data->pack(p3);
}
rc &= data->pack(nav_flag);
return data;
}
};
int main(int argc, char* argv[]) {
msp::FirmwareVariant fw_variant = msp::FirmwareVariant::INAV;
const std::string device =
(argc > 1) ? std::string(argv[1]) : "/dev/ttySUB0";
const size_t baudrate = (argc > 2) ? std::stoul(argv[2]) : 115200;
fcu::FlightController fcu;
fcu.setLoggingLevel(msp::client::LoggingLevel::INFO);
// wait for connection
fcu.connect(device, baudrate);
msp::msg::SetWp setwp(fw_variant);
setwp.wp_no = 255;
setwp.action = MSP_NAV_STATUS_WAYPOINT_ACTION_WAYPOINT;
setwp.lat = 40811854;
setwp.lon = 29360025;
setwp.alt = 1500;
setwp.p1 = 80;
setwp.p2 = 0;
setwp.p3 = 0;
setwp.nav_flag = 0;
if (fcu.sendMessage(setwp) ) {
std::cout << "Acknowled";
}
else
std::cout << "wasted";
} This is the final version of my code. I still couldn't solve my problem. I can't set a waypoint. |
@SALTU-19 Is comment #49 (comment) relevant to you? Does it work if you change the |
I edited it based on that comment but I still get an error:
I can't fix this :( |
@DC-SWAT i couldn't find the line that you've changed. could you tell me how can i find and change it more precisely? |
I used this info for MSP_SET_WP: Also need change uint32 to int32 in your code, for MSP_SET_WP and also for MSP_SONAR_ALTITUDE. |
Yes. For example your second |
I think that part of the code was deleted during copying. it was |
@DC-SWAT Have you ever used |
Just fix includes and replace SetWp in your code: #include <msp/Client.hpp>
#include <msp/FlightController.hpp>
// change
msp::msg::SetWp setwp(fw_variant);
// to
SetWp setwp(fw_variant); But anyway you got false from sendMessage, another fix is needed which I described above. Waypoint send normally, it's just wrong returned result. |
I moved the fix for the @SALTU-19 @DC-SWAT I would be happy if you could test this branch and send a PR that fixes remaining issues. |
i tried this code today and my drone is heavily broken.What do you think about this ? it did not go to the waypoint I gave it. @christianrauch Edit:A friend thinks that i try mspv2. What i am gonna do ? |
Was the If the new message definition is accepted by iNav, I will merge it into the repo and close this issue. |
ı didn’t get error. It was accept but it did not go to the waypoint i gave |
Thanks for checking this. This means that the wrong (or outdated) message definition caused the communication issue and that you can now send waypoints to iNav.
There are many reasons beyond the MSP communication why the FCU does not behave as intended. If the waypoint was received and accepted by the FC, then there is nothing more what this library can do. You should check the FCU logs for any issues or warnings. |
I entered the speed, altitude in cm and is there a problem due to the entry of latitude and longitude ? |
I am not sure what you are asking me. I have never used iNav, let alone it's waypoint functionality. On how to use the waypoint functionality, you would have to check the iNav documentation or the user forums. As far as I can tell from your feedback, the waypoint message ( |
i have f4 flight card with inav and raspberry pi zero.I want to send waypoint to my flight card with set_wp.I have an error("message v2 with id 209 is not recognized").What am i gonna do ?
@christianrauch
The text was updated successfully, but these errors were encountered: