solo sim parameters updated
This commit is contained in:
parent
d5f5852c12
commit
392531e131
|
@ -127,7 +127,8 @@ function pursuit() {
|
|||
if(neighbors.count() > 0)
|
||||
r_vec = math.vec2.scale(r_vec, 1.0 / neighbors.count())
|
||||
r = math.vec2.length(r_vec)
|
||||
gamma = vd / math.sqrt((r-rd)*(r-rd)+pc*pc*r*r)
|
||||
sqr = (r-rd)*(r-rd)+pc*pc*r*r
|
||||
gamma = vd / math.sqrt(sqr)
|
||||
dr = -gamma * (r-rd)
|
||||
dT = gamma * pc
|
||||
vfg = math.vec2.newp(r+dr*0.1, math.vec2.angle(r_vec)+dT*0.1)
|
||||
|
|
|
@ -6,17 +6,7 @@ topics:
|
|||
setpoint: mavros/setpoint_position/local
|
||||
armclient: mavros/cmd/arming
|
||||
modeclient: mavros/set_mode
|
||||
localpos: /mavros/local_position/pose
|
||||
stream: mavros/set_stream_rate
|
||||
localpos: mavros/local_position/pose
|
||||
stream: mavros/set_stream_rate
|
||||
altitude: mavros/global_position/rel_alt
|
||||
type:
|
||||
gps : sensor_msgs/NavSatFix
|
||||
# for SITL Solo
|
||||
# battery : mavros_msgs/BatteryState
|
||||
# for solo
|
||||
battery : mavros_msgs/BatteryStatus
|
||||
status : mavros_msgs/State
|
||||
altitude: std_msgs/Float64
|
||||
environment :
|
||||
environment : solo-simulator
|
||||
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
<!-- This file is included in all ROS workspace launch files -->
|
||||
<!-- Modify with great care! -->
|
||||
<launch>
|
||||
<arg name="name" default="robot0"/>
|
||||
<arg name="name" default="robot0"/>
|
||||
<arg name="xbee_plugged" default="true"/>
|
||||
<arg name="script" default="testalone"/>
|
||||
<arg name="launch_config" default="topics"/>
|
||||
|
|
|
@ -1001,8 +1001,7 @@ void roscontroller::SetStreamRate(int id, int rate, int on_off)
|
|||
ROS_INFO("Set stream rate call failed!, trying again...");
|
||||
ros::Duration(0.1).sleep();
|
||||
}
|
||||
// DEBUG
|
||||
// ROS_INFO("Set stream rate call successful");
|
||||
ROS_WARN("Set stream rate call successful");
|
||||
}
|
||||
|
||||
void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg)
|
||||
|
|
Loading…
Reference in New Issue