Project

General

Profile

Revision 6639ce9c

ID6639ce9c5b5ca4644e9f66e71b7d79bc24cf4fb0
Parent dfb92d66
Child 43b327cb

Added by viki over 11 years ago

Edited Sonar to display points on simulator.

Changed rate of sonar scan to 0.5s
Made a new wxDC graphics object for sonar

View differences:

scout/scoutsim/src/scout.h
109 109
    class Scout
110 110
    {
111 111
        public:
112
            Scout(const ros::NodeHandle& nh, const wxImage& scout_image,
113
                  const Vector2& pos, float orient);
112
            Scout(const ros::NodeHandle& nh,const wxImage& scout_image,
113
                  const Vector2& pos, wxBitmap *path_bitmap, float orient);
114 114

  
115 115
            geometry_msgs::Pose2D update(double dt, wxMemoryDC& path_dc,
116
					wxMemoryDC& sonar_dc,
116 117
                                         const wxImage& path_image,
117 118
                                         const wxImage& lines_image,
118 119
                                         const wxImage& walls_image,
119 120
                                         wxColour background_color,
121
         				 wxColour sonar_color,
120 122
                                         world_state state);
121 123
            void paint(wxDC& dc);
122 124

  
......
132 134
                                     unsigned char g,
133 135
                                     unsigned char b);
134 136
            unsigned int trace_sonar(const wxImage& walls_image, int x, int y,
135
                                     double robot_theta, int sonar_pos);
137
                                     double robot_theta, int sonar_pos,wxMemoryDC& sonar_dc);
136 138
            void update_sonar(const wxImage& walls_image, int x, int y,
137
                              double robot_theta);
139
                              double robot_theta, wxMemoryDC& sonar_dc);
138 140
            void update_linesensor(const wxImage& lines_image, int x, int y,
139 141
                                   double theta);
142
	    int old_dx;
143
	    int old_dy;
144
	    wxBitmap *path_bitmap;
140 145

  
141 146
            ros::NodeHandle node;
142 147

  

Also available in: Unified diff