Skip to content

Commit cec365d

Browse files
author
YH.Wang
committed
1.0.10 Update tm_foxy.md.
1 parent b61a7a5 commit cec365d

File tree

11 files changed

+15
-468
lines changed

11 files changed

+15
-468
lines changed

doc/tm_foxy.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,7 @@ The user can manually click the `Data Table Setting` <sup>2</sup> item and check
172172
>
173173
> ```bash
174174
> cd ~/<workspace> && source ./install/setup.bash
175-
> ros2 run tm_get_status image_talker
175+
> ros2 run tm_image image_talker
176176
> ```
177177
>
178178
> :bulb: The user can check whether the connection succeeds or not. When you proceed to the following steps introduced in the following text: step1 &rArr; step5 of § TMflow Vision node setup.

image_sub/src/sub_img.cpp

100644100755
Lines changed: 14 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -13,18 +13,18 @@
1313

1414

1515
class SubImg : public rclcpp::Node {
16-
private:
17-
cv::Mat image;
18-
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr imageSubscription;
19-
const std::string packageName = "image_sub";
20-
const std::string imageFileRelative = "/image/techman_robot.jpg";
21-
bool isShowPic;
22-
void get_new_image_callback(sensor_msgs::msg::Image::SharedPtr msg);
23-
void show_image();
16+
private:
17+
cv::Mat image;
18+
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr imageSubscription;
19+
const std::string packageName = "image_sub";
20+
const std::string imageFileRelative = "/image/techman_robot.jpg";
21+
bool isShowPic;
22+
void get_new_image_callback(sensor_msgs::msg::Image::SharedPtr msg);
23+
void show_image();
2424

25-
public:
26-
static int encoding_to_mat_type(const std::string & encoding);
27-
SubImg();
25+
public:
26+
static int encoding_to_mat_type(const std::string & encoding);
27+
SubImg();
2828
};
2929

3030
int SubImg::encoding_to_mat_type(const std::string & encoding){
@@ -60,13 +60,14 @@ void SubImg::get_new_image_callback(sensor_msgs::msg::Image::SharedPtr msg){
6060
}
6161
std::cout << "Width : " << frame.size().width << std::endl;
6262
std::cout << "Height: " << frame.size().height << std::endl;
63-
frame.copyTo(this->image);
63+
frame.copyTo(this->image);
6464
std::cout<<"after set this->image = frame";
6565
}
6666
catch(std::runtime_error &exception){
6767
std::cout<<"there is a exception "<< exception.what()<< std::endl;
6868
}
6969
}
70+
7071
void SubImg::show_image(){
7172
while(true){
7273
cv::imshow("showimage",this->image );
@@ -89,5 +90,6 @@ int main(int argc, char *argv[]){
8990
rclcpp::spin(std::make_shared<SubImg>());
9091
std::cout<<"end spin"<<std::endl;
9192
rclcpp::shutdown();
93+
9294
return 0;
9395
}

techman_robot_get_status/package.xml

Lines changed: 0 additions & 17 deletions
This file was deleted.

techman_robot_get_status/resource/tm_get_status

Whitespace-only changes.

techman_robot_get_status/setup.cfg

Lines changed: 0 additions & 4 deletions
This file was deleted.

techman_robot_get_status/setup.py

Lines changed: 0 additions & 28 deletions
This file was deleted.

techman_robot_get_status/tm_get_status/__init__.py

Whitespace-only changes.

techman_robot_get_status/tm_get_status/get_status.py

Lines changed: 0 additions & 62 deletions
This file was deleted.

techman_robot_get_status/tm_get_status/image_pub.py

Lines changed: 0 additions & 213 deletions
This file was deleted.

0 commit comments

Comments
 (0)