Closed Ahrovan closed 7 years ago
Did you already clarified this on the Arducopter channels?
No, today working on it
Hello, please use global or local setpoint in guided mode and not MAV_CMD_NAV_WAYPOINT. To use MAV_CMD_NAV_WAYPOINT like in dronekit/mavproxy/etc you need to set current field to 2 (http://mavlink.org/messages/common#COMMAND_INT) see https://github.com/ArduPilot/MAVProxy/blob/b2452edc85c6d8c83cc258e3e6219ac9b1268675/MAVProxy/modules/mavproxy_mode.py#L73
Thanks for clarifying this Pierre.
I can not solve that. I have two way and confusing
rostopic pub /mavros/mission/waypoints vros_msgs/WaypointList rostopipub /mavros/setpoint_raw/global mavros_msgs/GlobalPositionTarget or other way can be found?
I check simple_goto function and see this:
self._master.mav.mission_item_send(0, 0, 0, frame, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2, 0, 0, 0, 0, 0, location.lat, location.lon, alt)
and try with mavros:
rostopic pub /mavros/mission/waypoints vros_msgs/WaypointList "waypoints:
@khancyr is_current is bool! `# see enum MAV_CMD and CommandCode.msg uint16 command
bool is_current bool autocontinue`
@khancyr are you say we can not use MAV_CMD_NAV_WAYPOINT in MAV_FRAME_GLOBAL_RELATIVE_ALT frame with mavros?
I have not found a solution to this problem
any idea?!
When we using the software (Mission planner or QGC or APM Planner), right-click on the map and set target in GUIDED flight mode. then Arducopter start move to Specified coordinates (lat,lon). Now. I want to do this by programming. This done by drone-kit simplegoto function (referenced here) But I intend to do it with mavros (c++). I do not know exactly which topic of mavros should be used (some one say SET_POSITION_TARGET_GLOBAL_INT with setpointraw But it did not work) and how to use it. Of course I'm familiar with mavros and I'm not beginner in this.
I check qgroundstation code and see: `void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly) { if (inProgress()) { qCDebug(MissionManagerLog) << "writeArduPilotGuidedMissionItem called while transaction in progress"; return; }
_transactionInProgress = TransactionWrite;
_connectToMavlink();
mavlink_message_t messageOut;
mavlink_mission_item_t missionItem;
memset(&missionItem, 8, sizeof(missionItem));
missionItem.target_system = _vehicle->id();
missionItem.target_component = _vehicle->defaultComponentId();
missionItem.seq = 0;
missionItem.command = MAV_CMD_NAV_WAYPOINT;
missionItem.param1 = 0;
missionItem.param2 = 0;
missionItem.param3 = 0;
missionItem.param4 = 0;
missionItem.x = gotoCoord.latitude();
missionItem.y = gotoCoord.longitude();
missionItem.z = gotoCoord.altitude();
missionItem.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
missionItem.current = altChangeOnly ? 3 : 2;
missionItem.autocontinue = true;
_dedicatedLink = _vehicle->priorityLink();
mavlink_msg_mission_item_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_dedicatedLink->mavlinkChannel(),
&messageOut,
&missionItem);
_vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
_startAckTimeout(AckGuidedItem);
emit inProgressChanged(true);
}`
missionItem.current = altChangeOnly ? 3 : 2; is bool or uint8 ? rostopic pub -r 10 /mavros/mission/waypointmavros_msgs/WaypointList "waypoints:- {frame: 0, command: 0, is_current: false, autocontinue: false, param1: 0.0, param2: 0.0, param3: 0.0, param4: 0.0, x_lat: 0.0, y_long: 0.0, z_alt: 0.0}" is_current is Boolean type in Waypoint
you need to publish in mavros/setpoint_raw/global then check you coordinate frame and your mask for position only : 0b0000111111111000 == 4088 works
Thank you very much @khancyr
Problem solved :)
Does this work for ArduPlane also? I tried doing it but it didnt work. I plan to update the location of guided waypoint for plane. How can it be done?
Any development on this topic? Im also trying to implement the Local position and velocity setpoints but with no luck
The following code works for position on a simulated copter that is already in the air in GUIDED mode:
import rospy
from mavros_msgs.msg import GlobalPositionTarget
from time import sleep
rospy.init_node('my_cool_node')
guided_waypoint_pub = rospy.Publisher('/mavros/setpoint_raw/global', GlobalPositionTarget, queue_size=1)
while guided_waypoint_pub.get_num_connections() == 0:
sleep(.1)
g = GlobalPositionTarget()
g.altitude = ...
g.latitude = ...
g.longitude = ...
g.type_mask=4088
g.coordinate_frame=6
guided_waypoint_pub.publish(g)
Hi guys, @khancyr @vooon @TSC21 @Ahrovan @Akshath-Singhal @LightningPORTO Were you able to navigate the drone to multiple waypoints? I am also trying to accomplish the same in ardupilot (GUIDED mode) and using mavros_msgs::GlobalPositionTarget but end up with issues. Please if you could refer to https://github.com/mavlink/mavros/issues/1553 and help me with the issues, I would be very grateful. Thanks in advance!
dronekit use simple_goto and mavlink code
self._master.mav.mission_item_send(0, 0, 0, frame, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2, 0, 0, 0, 0, 0, location.lat, location.lon, alt)
for sent specific location for guided mode. but when use MAV_CMD_NAV_WAYPOINT in mavros says:rosrun mavros mavcmd long 16 0 0 0 0 0 0 1 Request failed. Check mavros logs. ACK: 3
in dev page copter-commands-in-guided-mode , I dont see MAV_CMD_NAV_WAYPOINT. but in GCS softwares(mission planner+apm planner+SITL_MAP ..) we can click on map and DO fly to, go to here in GUIDED mode. What is solution?Mavros: 0.18.4 ROS: Kinetic Ubuntu: 16.04 [OK] ArduPilot Last