Skip to content

Commit

Permalink
[fix] fixed simulation config.
Browse files Browse the repository at this point in the history
  • Loading branch information
cyanine-gi committed Aug 2, 2021
1 parent 974f3f5 commit 0c2539e
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 9 deletions.
4 changes: 2 additions & 2 deletions simulation/scripts/prepare_simulation.sh
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,14 @@ export DRONE_ITEM="iris_stereo_rgb_gpulidar_gps"
#export DRONE_ITEM="standard_vtol"
#export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/obstacle_avoidance.world
#export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/obstacle_avoidance_without_iris.world
export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/obstacle_avoidance_with_unknown_obstacle.world
#export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/obstacle_avoidance_with_unknown_obstacle.world

#source /usr/local/share/citysim/setup.sh
#export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/simple_city.world # need to run 'source /usr/local/share/citysim/setup.sh'


#export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/park_large.world
#export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/park_large_without_iris.world
export WORLD_ITEM=$PX4_ENV_PATH$SF/Tools/sitl_gazebo/worlds/park_large_without_iris.world
#To use iris_vision, you need to copy files from GAAS. See Readme.md.

echo "COMMAND: roslaunch px4 $LAUNCH_FILE vehicle:=$DRONE_ITEM"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,10 +145,10 @@ LidarCloudT::Ptr toPointCloud(cv::Mat& depth_masked)
// x*=z/len;
// y*=z/len;
// z*=z/len;
PointT pt;
pt.x = x;
pt.y = y;
pt.z = z;
PointT pt;//For downward lidar placing:
pt.x = -y;
pt.y = -x;
pt.z = -z;
newcloud->push_back(pt);
}
}
Expand Down Expand Up @@ -178,16 +178,16 @@ void callback(const sensor_msgs::ImageConstPtr& img_msg)
sensor_msgs::PointCloud2 cloud_msg;
pcl::toROSMsg(*pCloud,cloud_msg);
cloud_msg.header.stamp = ros::Time::now();
cloud_msg.header.frame_id = "livox";
cloud_msg.header.frame_id = "lidar";//"livox";
pPub->publish(cloud_msg);

}
int main(int argc,char** argv)
{
FLAGS_alsologtostderr = 1;
google::InitGoogleLogging(argv[0]);
LOG(INFO)<<"Start vision_lidar_fusion_node."<<endl;
ros::init(argc,argv,"vision_lidar_fusion_node");
LOG(INFO)<<"Start livox_horizon_sim_node."<<endl;
ros::init(argc,argv,"livox_horizon_sim_node");
ros::NodeHandle nh;
pNH=&nh;
LivoxHorizonSim liv;
Expand Down

0 comments on commit 0c2539e

Please sign in to comment.