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

Mavros angular velocity

asked 2021-09-02 13:19:59 -0500

subarashi gravatar image

Hello Dear community.

I am running a simple code to flight the drone in off-board mode. The drone reach an altitude of 1.6 meters without problems. Now I would like to rotate the drone over the Z axes. I am able to do that with the below code but rotation of the drone in the real life is to fast and I want to decrease that angular velocity. How can I rotate over the Z axis with slow angular velocity?

This is my code:

import rospy
import ast
import mavros
from std_msgs.msg import String
from geometry_msgs.msg import Point
from geometry_msgs.msg import Pose
from time import sleep
import re
from tf.transformations import quaternion_from_euler
import numpy as np
from time import sleep
mavros.set_namespace()

class data_processing():
    def __init__(self):
        self.yawVal = 0
        self.sub = rospy.Subscriber("/Face_recognition/Searching", String, self.callback) 


    def callback(self, data):
        two_pi = 2*3.14159265359
        pose = Pose()
        #velocity_msg = Twist()
        if data.data =="Searching"and self.yawVal<two_pi:

            X = 0
            Y = 0
            Z = 1.6
            rVal = 0
            pVal = 0 
            self.yawVal += 0.1
            print("Yaw value: ", self.yawVal) 
            pose.position.x = X
            pose.position.y = Y
            pose.position.z = Z
            quat = quaternion_from_euler(rVal, pVal, self.yawVal)
            pose.orientation.x = quat[0]
            pose.orientation.y = quat[1]
            pose.orientation.z = quat[2]
            pose.orientation.w = quat[3]
            #print("position: ", pose.orientation)
            pub.publish(pose)


        else:
            self.yawVal = 0 



if __name__ == "__main__":
    print("Searching node ready")
    rospy.init_node('Searching_node', anonymous=True)
    pub = rospy.Publisher('/Face_recognition/coordinates', Pose, queue_size=10)
    rate = rospy.Rate(10)  # 10hz
    drone_data = data_processing()
    rospy.spin()

The topic /Face_recognition/coordinates publish to one node who publish to mavros. Should I use /mavros/local_position/pose and /mavros/local_position/velocity? I need help please.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2021-09-03 02:17:38 -0500

Ranjit Kathiriya gravatar image

updated 2021-09-03 03:05:51 -0500

Hello @subarashi,

I would suggest you to have a look at the basic coordinate system of drones.

According to my opinion, I think that It is better to use the Twist message instead of Pose.

msg = Twist() 
drone pitch(msg.linear.x)
drone  roll(msg.linear.y)     
drone  throttle(msg.linear.z)
drone yaw(msg.angular.z)     # pose.orientation.z you can directly set it

You can ignore all other messages orientation: x,y and w so you don't need to do quaternion_from_euler.
Anyways, you can use this message also.

How can I rotate over the Z axis with slow angular velocity?

I think over here, the issue is with your code.

self.yawVal += 0.1 # Over here it is adding the 0.1 and this number is getting big and due to that, you can see fast moments in your drone. instead, we just want to publish data that tells the drone to just move 0.1 from the current location. Now, yawVal = 0.1 with this every published drone will move just 0.1 meters from the current distance. Note if you want to slow it to more then go with lower limits of 0.01.

edit flag offensive delete link more

Comments

Thank you so much for your reply. I will take a look at what you mention. self.yawVal += 0.1 I am adding 0,1 because the rotation must be 360 degrees and that means from 0 to 2pi radians. yawVal = 0.1 is in radian units I guess. I need to mention that I am using PX4, Pixhawak 4, Ros melodic, and T265 realsense-camera.

subarashi gravatar image subarashi  ( 2021-09-03 04:13:30 -0500 )edit

Just have a look at the standard ros coordinate system.

Here is a formula for the degree to the radiant have a look at this this can help you easily converting degree to radiant.

360Deg × π/180 = 6.283Rad

As you maintained above move your drone 360Deg and its radiant would be around 6.283 Red. As I told you don't require to convert it into quaternion_from_euler.

Can you have a look at this also: I may be wrong also I think that after conversion your drone may get another number instead of a proper Red value. Note: I may be wrong also.

Ranjit Kathiriya gravatar image Ranjit Kathiriya  ( 2021-09-03 04:25:04 -0500 )edit

well I need to convert euler to quaternion because I want to rotate over the Z axes. Because I need to rotate the Yaw angle I send the values from 0.0 to 6.283 rad so after it I convert to quaternion to be able to rotate the drone. In the same way, I do not understand how Twist works, because I am also doing position control moving from one place to other place, so Twist move the drone from one point to other point or just adjust the specified velocity?

subarashi gravatar image subarashi  ( 2021-09-03 06:21:34 -0500 )edit

Question Tools

Stats

Asked: 2021-09-02 13:19:59 -0500

Seen: 363 times

Last updated: Sep 03 '21