ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

How to send velocity to pixhawk with Mavros?

asked 2015-04-13 19:15:02 -0500

alexandre28 gravatar image

Hi guys,

after searching a lot and don't get a solution I would like a help. I am a new user of Mavros package and I have some doubts about it. My setup for tests is:

1 Pixhawk with ArduCopter V3.2.1Quad firmware, 1 ESC 20A SkyWalker, 1 motor, 1 GPS+Compass, 1 radio receiver and 1 battery. I installed mavros on Indigo and ubuntu 14.04.

I want to start sending a simple command of linear velocity to pixhawk, for example vx = 1 m/s.

I typed the commands bellow in sequence:

1) sudo chmod 666 /dev/ttyACM0

2) roslaunch mavros px4.launch

3) rosrun mavros mavsafety arm

4) and my code: rosrun copter velocity

After that nothing happened. The the motor spun with default velocity of the node mavsafety arm and not with desired velocity.

What topic should I publish this message?

I checked the topic /mavros/setpoint_attitude/cmd_vel and the value that I set in the source code was there.

So, where is the mistake? Should I do some setup before to run?

I read at some forum people talking about some setup that we have to do...but is not clear for me.

Can anyone show a piece of code that make what I want or give me a tips?

Thank you!

I wrote a code trying to do this but without successful.

#include <ros/ros.h>
#include <std_msgs/String.h> 
#include <stdio.h>
#include "geometry_msgs/TwistStamped.h"
#include "geometry_msgs/Vector3Stamped.h"

int main(int argc, char **argv)
{
   ros::init(argc, argv, "comun");
   ros::NodeHandle n;

   ros::Publisher chatter_pub = n.advertise<geometry_msgs::TwistStamped>("/mavros/setpoint_attitude/cmd_vel",100);
   ros::Rate loop_rate(10);

   geometry_msgs::TwistStamped msg;

   while(ros::ok()){
       msg.header.stamp = ros::Time::now();
       msg.header.seq=1;
       msg.twist.linear.x = 1;
       msg.twist.angular.x = 1;

       chatter_pub.publish(msg);
       ros::spinOnce();
       loop_rate.sleep();
   }    
   return 0;
}
edit retag flag offensive close merge delete

5 Answers

Sort by ยป oldest newest most voted
0

answered 2015-04-15 10:33:21 -0500

alexandre28 gravatar image

I did which you suggest,

2) roslaunch mavros apm.launch

3) rosrun mavros mavsafety arm

4) rosrun mavros mavsys mode -c GUIDED that resulted: Mode changed

5) and ran my code (with just yaw rotation -> twist.angular.z)

but nothing happened. The motor is spinning with default velocity when the pixhawk is armed.

The topic that am I publishing is correct? (/mavros/setpoint_attitude/cmd_vel)

edit flag offensive delete link more

Comments

Topic correct (you may check by rqt_graph). Also try position sp. Note that SP support is new in APM, not sure that it exist in latest stable release.

vooon gravatar image vooon  ( 2015-04-15 11:45:16 -0500 )edit
1

answered 2016-03-15 16:05:37 -0500

srikanthmalla gravatar image

may be you should try: /mavros/setpoint_velocity/cmd_vel (geometry_msgs/TwistStamped)

Velocity setpoint.

edit flag offensive delete link more
0

answered 2015-12-10 16:43:27 -0500

omar gravatar image

I've been trying to send yaw (radians/degrees) to rotate the UAV Quadcompter using ros + mavros + SITL(to connect fcu with mavproxy), I now can read that apm is not supported yet, however, I used roslaunch mavros px4.launch fcu_url ... and nothing different append. The version that I use is mavros 0.16.3, I've armed, changed to guided mode and takeoff. The success that I have until today is related with moving the quadcopter in the sitl to go forward, go back, left, etc-- all before is having a publisher in /mavros/setpoint_velocity/cmd_vel..

Is there anyway to rotate the quadcopter in the desired degrees keeping the same alttitude?

Thanks.

edit flag offensive delete link more
0

answered 2015-04-15 05:31:21 -0500

vooon gravatar image

2) You should use apm.launch , did you read: http://wiki.ros.org/mavros#Usage ?

After arming setpoint also require enabling specific mode, GUIDED for APM and OFFBOARD for PX4.

 rosrun mavros mavsys mode -c GUIDED

Next: velocity only supports YAW rotation (twist.angular.z), read source it's very simple: link.

edit flag offensive delete link more
0

answered 2015-04-28 18:33:49 -0500

alce gravatar image

I am not expert in offboard mode. I have the same problem with this attitude topic I just want some help please. and I am using ROS indigo.

As I can see the topic /mavros/setpoint_velocity/cmd_vel generates a change in velocity in the motors and seem works, but when I publish /mavros/setpoint_attitude/cmd_vel I can't observe any change only in the value of the topic. The OFFBOARD mode is not not refusing my command. I try using: msg.twist.linear.x = 100 and other different values also I try with msg.twist.angular.z =100 but none works Anybody knows what could be the mistake and how to update this in order to publish velocity commands?

edit flag offensive delete link more

Comments

I don't see support for SET_ATTITUDE_TARGET in APM code. Or you used PX4?

vooon gravatar image vooon  ( 2015-04-29 04:03:03 -0500 )edit

I am using PX4. I want to move linear using a velocity command and to make a short rotation with a fraction of \pi. for example pi/6 CCW. I don't know what message could be appropiate

I am able to send commands with /mavros/setpoint_velocity/cmd_vel but I am not sure of behaviour flying. Thanks

alce gravatar image alce  ( 2015-05-05 17:51:52 -0500 )edit

As i know currently velocity sp's broken in PX4 master. Also note that attitude twist only uses angular part.

vooon gravatar image vooon  ( 2015-05-06 01:58:08 -0500 )edit

Excuse me, do you know if exist any way of generate linear velocity commands in x and y with mavros and pixhawk with px4. If the velocity sp's are broken, Do I have to change the firmware? or is a problem with mavros? How could I get some help with this problem? please

alce gravatar image alce  ( 2015-06-02 18:06:07 -0500 )edit

Try to update to latest firmware. PX4 development is very fast, so probably sp handler are fixed.

vooon gravatar image vooon  ( 2015-06-03 04:15:51 -0500 )edit

Thanks, I update the firmware, but I would like to take off my quadrotor and after do a linear command. The first stage is done with set position (it is working ok) and after that I am trying to use a linear velocity command, but I am not sure if the actual sp allow to do that now?

alce gravatar image alce  ( 2015-06-03 22:15:09 -0500 )edit

Don't mix setpoint types, it may cause errors.

vooon gravatar image vooon  ( 2015-06-04 00:17:24 -0500 )edit

ok I will. Some questions please. Do you know the units of linear in this kind of commands msg.twist.linear.y? I am trying to taking off by using the sp velocity but nothing any idea? Do you know how to reduce the max velocity in position sp's?, because the changes of positions are too strong Thanks

alce gravatar image alce  ( 2015-06-05 22:55:15 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2015-04-13 19:15:02 -0500

Seen: 11,659 times

Last updated: Mar 15 '16